RosCartesianAccelerationPID.h
Go to the documentation of this file.
1 //| This file is a part of the ORCA framework.
2 //|
3 //| Copyright 2018, Fuzzy Logic Robotics
4 //| Copyright 2017, ISIR / Universite Pierre et Marie Curie (UPMC)
5 //|
6 //| Main contributor(s): Antoine Hoarau, Ryan Lober, and
7 //| Fuzzy Logic Robotics <info@fuzzylogicrobotics.com>
8 //|
9 //| ORCA is a whole-body reactive controller framework for robotics.
10 //|
11 //| This software is governed by the CeCILL-C license under French law and
12 //| abiding by the rules of distribution of free software. You can use,
13 //| modify and/ or redistribute the software under the terms of the CeCILL-C
14 //| license as circulated by CEA, CNRS and INRIA at the following URL
15 //| "http://www.cecill.info".
16 //|
17 //| As a counterpart to the access to the source code and rights to copy,
18 //| modify and redistribute granted by the license, users are provided only
19 //| with a limited warranty and the software's author, the holder of the
20 //| economic rights, and the successive licensors have only limited
21 //| liability.
22 //|
23 //| In this respect, the user's attention is drawn to the risks associated
24 //| with loading, using, modifying and/or developing or reproducing the
25 //| software by the user in light of its specific status of free software,
26 //| that may mean that it is complicated to manipulate, and that also
27 //| therefore means that it is reserved for developers and experienced
28 //| professionals having in-depth computer knowledge. Users are therefore
29 //| encouraged to load and test the software's suitability as regards their
30 //| requirements in conditions enabling the security of their systems and/or
31 //| data to be ensured and, more generally, to use and operate it in the
32 //| same conditions as regards security.
33 //|
34 //| The fact that you are presently reading this means that you have had
35 //| knowledge of the CeCILL-C license and that you accept its terms.
36 
37 #pragma once
38 #include "orca/common/CartesianAccelerationPID.h"
41 
42 namespace orca_ros
43 {
44  namespace common
45  {
46 
48  {
49  public:
50  RosCartesianAccelerationPID(const std::string& robot_name,
51  const std::string& controller_name,
52  const std::string& task_name,
53  std::shared_ptr<orca::common::CartesianAccelerationPID> cart_acc_pid);
55 
56  public:
57  bool setDesiredService(orca_ros::SetDesired::Request &req, orca_ros::SetDesired::Response &res);
58  bool getCommandService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res);
59  bool getCurrentCartesianPoseService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res);
60  bool getCurrentCartesianVelocityService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res);
61  bool getDesiredCartesianPoseService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res);
62  bool getDesiredCartesianVelocityService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res);
63  bool getDesiredCartesianAccelerationService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res);
64  bool printService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
65 
66  private:
67  std::shared_ptr<orca::common::CartesianAccelerationPID> cart_acc_pid_;
68  std::shared_ptr<RosPIDController> internal_pid_wrapper_;
69 
70  ros::ServiceServer ss_setDesired_;
71  ros::ServiceServer ss_getCommand_;
72  ros::ServiceServer ss_getCurrentCartesianPose_;
73  ros::ServiceServer ss_getCurrentCartesianVelocity_;
74  ros::ServiceServer ss_getDesiredCartesianPose_;
75  ros::ServiceServer ss_getDesiredCartesianVelocity_;
76  ros::ServiceServer ss_getDesiredCartesianAcceleration_;
77  ros::ServiceServer ss_print_;
78  };
79  }
80 }
Definition: RosWrapperBase.h:50
bool getCurrentCartesianPoseService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res)
Definition: RosCartesianAccelerationPID.cc:46
~RosCartesianAccelerationPID()
Definition: RosCartesianAccelerationPID.cc:24
Definition: RosCartesianAccelerationPID.h:42
bool getCommandService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res)
Definition: RosCartesianAccelerationPID.cc:40
bool getDesiredCartesianAccelerationService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res)
Definition: RosCartesianAccelerationPID.cc:70
Definition: RosCartesianAccelerationPID.h:47
bool setDesiredService(orca_ros::SetDesired::Request &req, orca_ros::SetDesired::Response &res)
Definition: RosCartesianAccelerationPID.cc:29
bool getCurrentCartesianVelocityService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res)
Definition: RosCartesianAccelerationPID.cc:52
RosCartesianAccelerationPID(const std::string &robot_name, const std::string &controller_name, const std::string &task_name, std::shared_ptr< orca::common::CartesianAccelerationPID > cart_acc_pid)
Definition: RosCartesianAccelerationPID.cc:5
bool getDesiredCartesianVelocityService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res)
Definition: RosCartesianAccelerationPID.cc:64
bool getDesiredCartesianPoseService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res)
Definition: RosCartesianAccelerationPID.cc:58
bool printService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: RosCartesianAccelerationPID.cc:76