40 #include <orca/task/GenericTask.h> 51 const std::string& controller_name,
52 std::shared_ptr<orca::task::GenericTask> gen_task);
57 orca_ros::GetDouble::Response& res
60 orca_ros::SetDouble::Response& res
63 orca_ros::GetSize::Response& res
66 orca_ros::GetInt::Response& res
69 orca_ros::GetInt::Response& res
71 bool getEService( orca_ros::GetMatrix::Request& req,
72 orca_ros::GetMatrix::Response& res
74 bool getfService( orca_ros::GetMatrix::Request& req,
75 orca_ros::GetMatrix::Response& res
78 std_srvs::Empty::Response& res
80 bool setEService( orca_ros::SetMatrix::Request& req,
81 orca_ros::SetMatrix::Response& res
83 bool setfService( orca_ros::SetMatrix::Request& req,
84 orca_ros::SetMatrix::Response& res
91 std::shared_ptr<orca::task::GenericTask> gt_;
93 ros::ServiceServer ss_getWeightService_;
94 ros::ServiceServer ss_setWeightService_;
95 ros::ServiceServer ss_getSizeService_;
96 ros::ServiceServer ss_colsService_;
97 ros::ServiceServer ss_rowsService_;
98 ros::ServiceServer ss_getEService_;
99 ros::ServiceServer ss_getfService_;
100 ros::ServiceServer ss_printService_;
101 ros::ServiceServer ss_setEService_;
102 ros::ServiceServer ss_setfService_;
bool getEService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res)
Definition: RosGenericTask.cc:55
virtual ~RosGenericTask()
Definition: RosGenericTask.cc:23
Definition: RosTaskBase.h:47
bool setfService(orca_ros::SetMatrix::Request &req, orca_ros::SetMatrix::Response &res)
Definition: RosGenericTask.cc:77
bool getSizeService(orca_ros::GetSize::Request &req, orca_ros::GetSize::Response &res)
Definition: RosGenericTask.cc:38
bool setWeightService(orca_ros::SetDouble::Request &req, orca_ros::SetDouble::Response &res)
Definition: RosGenericTask.cc:33
RosGenericTask(const std::string &robot_name, const std::string &controller_name, std::shared_ptr< orca::task::GenericTask > gen_task)
Definition: RosGenericTask.cc:5
bool getWeightService(orca_ros::GetDouble::Request &req, orca_ros::GetDouble::Response &res)
Definition: RosGenericTask.cc:28
Definition: RosCartesianAccelerationPID.h:42
bool printService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: RosGenericTask.cc:67
bool getfService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res)
Definition: RosGenericTask.cc:61
bool setEService(orca_ros::SetMatrix::Request &req, orca_ros::SetMatrix::Response &res)
Definition: RosGenericTask.cc:72
bool colsService(orca_ros::GetInt::Request &req, orca_ros::GetInt::Response &res)
Definition: RosGenericTask.cc:45
Definition: RosGenericTask.h:47
bool rowsService(orca_ros::GetInt::Request &req, orca_ros::GetInt::Response &res)
Definition: RosGenericTask.cc:50