38 #include "orca/common/CartesianAccelerationPID.h" 51 const std::string& controller_name,
52 const std::string& task_name,
53 std::shared_ptr<orca::common::CartesianAccelerationPID> cart_acc_pid);
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);
64 bool printService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
67 std::shared_ptr<orca::common::CartesianAccelerationPID> cart_acc_pid_;
68 std::shared_ptr<RosPIDController> internal_pid_wrapper_;
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_;
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