50 const std::string& controller_name,
51 const std::string& task_name);
55 std::shared_ptr<RosPIDControllerProxy>
pid();
58 void setDesired(
const Eigen::Matrix4d& cartesian_position_traj,
59 const orca::math::Vector6d& cartesian_velocity_traj,
60 const orca::math::Vector6d& cartesian_acceleration_traj);
70 std::shared_ptr<RosPIDControllerProxy> internal_pid_proxy_;
73 ros::ServiceClient sc_setDesired_;
74 ros::ServiceClient sc_getCommand_;
75 ros::ServiceClient sc_getCurrentCartesianPose_;
76 ros::ServiceClient sc_getCurrentCartesianVelocity_;
77 ros::ServiceClient sc_getDesiredCartesianPose_;
78 ros::ServiceClient sc_getDesiredCartesianVelocity_;
79 ros::ServiceClient sc_getDesiredCartesianAcceleration_;
80 ros::ServiceClient sc_print_;
std::shared_ptr< RosPIDControllerProxy > pid()
Definition: RosCartesianAccelerationPIDProxy.cc:28
Eigen::Matrix4d getCurrentCartesianPose()
Definition: RosCartesianAccelerationPIDProxy.cc:59
Definition: RosWrapperBase.h:50
orca::math::Vector6d getDesiredCartesianAcceleration()
Definition: RosCartesianAccelerationPIDProxy.cc:108
orca::math::Vector6d getCurrentCartesianVelocity()
Definition: RosCartesianAccelerationPIDProxy.cc:71
void setDesired(const Eigen::Matrix4d &cartesian_position_traj, const orca::math::Vector6d &cartesian_velocity_traj, const orca::math::Vector6d &cartesian_acceleration_traj)
Definition: RosCartesianAccelerationPIDProxy.cc:33
orca::math::Vector6d getCommand()
Definition: RosCartesianAccelerationPIDProxy.cc:47
RosCartesianAccelerationPIDProxy(const std::string &robot_name, const std::string &controller_name, const std::string &task_name)
Definition: RosCartesianAccelerationPIDProxy.cc:5
Definition: RosCartesianAccelerationPID.h:42
void print()
Definition: RosCartesianAccelerationPIDProxy.cc:120
Eigen::Matrix4d getDesiredCartesianPose()
Definition: RosCartesianAccelerationPIDProxy.cc:83
~RosCartesianAccelerationPIDProxy()
Definition: RosCartesianAccelerationPIDProxy.cc:23
orca::math::Vector6d getDesiredCartesianVelocity()
Definition: RosCartesianAccelerationPIDProxy.cc:95
Definition: RosCartesianAccelerationPIDProxy.h:46