39 #include "orca/task/CartesianTask.h" 53 const std::string& controller_name,
54 std::shared_ptr<orca::task::CartesianTask> cart_task);
59 bool setDesiredService(orca_ros::SetMatrix::Request &req, orca_ros::SetMatrix::Response & res);
60 bool setBaseFrameService(orca_ros::SetString::Request &req, orca_ros::SetString::Response & res);
61 bool setControlFrameService(orca_ros::SetString::Request &req, orca_ros::SetString::Response & res);
62 bool getBaseFrameService(orca_ros::GetString::Request &req, orca_ros::GetString::Response & res);
63 bool getControlFrameService(orca_ros::GetString::Request &req, orca_ros::GetString::Response & res);
66 void publishCurrentState();
67 void desiredStateSubscriberCb(
const orca_ros::CartesianTaskState::ConstPtr& msg);
70 std::shared_ptr<orca::task::CartesianTask> cart_task_;
71 std::shared_ptr<orca::common::CartesianAccelerationPID> cart_servo_;
72 std::shared_ptr<orca_ros::common::RosCartesianAccelerationPID> cart_servo_wrapper_;
74 ros::ServiceServer ss_setDesired_;
75 ros::ServiceServer ss_setBaseFrame_;
76 ros::ServiceServer ss_setControlFrame_;
77 ros::ServiceServer ss_getBaseFrame_;
78 ros::ServiceServer ss_getControlFrame_;
81 ros::Publisher current_state_pub_;
82 ros::Subscriber desired_state_sub_;
83 orca_ros::CartesianTaskState current_state_msg_;
RosCartesianTask(const std::string &robot_name, const std::string &controller_name, std::shared_ptr< orca::task::CartesianTask > cart_task)
Definition: RosCartesianTask.cc:5
Definition: RosCartesianTask.h:49
virtual ~RosCartesianTask()
Definition: RosCartesianTask.cc:28
Definition: RosCartesianAccelerationPID.h:42
Definition: RosGenericTask.h:47