39 #include <orca/common/TaskBase.h> 51 const std::string& controller_name,
52 const std::string& generic_prefix,
53 std::shared_ptr<orca::common::TaskBase> base);
58 bool isActivatedService( orca_ros::GetBool::Request& req,
59 orca_ros::GetBool::Response& res
61 bool getNameService( orca_ros::GetString::Request& req,
62 orca_ros::GetString::Response& res
64 bool activateService( orca_ros::GetBool::Request& req,
65 orca_ros::GetBool::Response& res
67 bool deactivateService( orca_ros::GetBool::Request& req,
68 orca_ros::GetBool::Response& res
70 bool printService( std_srvs::Empty::Request& req,
71 std_srvs::Empty::Response& res
73 bool getStateService( orca_ros::GetEnum::Request& req,
74 orca_ros::GetEnum::Response& res
76 bool setRampDurationService(orca_ros::SetDouble::Request& req,
77 orca_ros::SetDouble::Response& res
79 bool getRampDurationService(orca_ros::GetDouble::Request& req,
80 orca_ros::GetDouble::Response& res
85 std::shared_ptr<orca::common::TaskBase> base_;
87 ros::ServiceServer ss_isActivated_;
88 ros::ServiceServer ss_getName_;
89 ros::ServiceServer ss_activate_;
90 ros::ServiceServer ss_deactivate_;
91 ros::ServiceServer ss_print_;
92 ros::ServiceServer ss_getState_;
93 ros::ServiceServer ss_setRampDuration_;
94 ros::ServiceServer ss_getRampDuration_;
Definition: RosWrapperBase.h:50
Definition: RosTaskBase.h:47
Definition: RosCartesianAccelerationPID.h:42
virtual ~RosTaskBase()
Definition: RosTaskBase.cc:23
RosTaskBase(const std::string &robot_name, const std::string &controller_name, const std::string &generic_prefix, std::shared_ptr< orca::common::TaskBase > base)
Definition: RosTaskBase.cc:5