40 #include <orca/optim/Controller.h> 53 std::shared_ptr<orca::optim::Controller> c,
54 bool attach_torque_publish_callback =
false);
58 bool getNameService(orca_ros::GetString::Request &req, orca_ros::GetString::Response &res);
59 bool printService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
61 bool updateService(orca_ros::UpdateController::Request &req, orca_ros::UpdateController::Response &res);
62 bool addTaskService(orca_ros::AddTask::Request &req, orca_ros::AddTask::Response &res);
63 bool addConstraintService(orca_ros::AddConstraint::Request &req, orca_ros::AddConstraint::Response &res);
64 bool getSolutionService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res);
72 void publishJointTorqueCommands();
75 std::shared_ptr<orca::optim::Controller> ctrl_;
77 ros::ServiceServer ss_getName_;
78 ros::ServiceServer ss_print_;
79 ros::ServiceServer ss_setPrintLevel_;
80 ros::ServiceServer ss_update_;
81 ros::ServiceServer ss_addTask_;
82 ros::ServiceServer ss_addConstraint_;
83 ros::ServiceServer ss_getSolution_;
84 ros::ServiceServer ss_getJointTorqueCommand_;
85 ros::ServiceServer ss_getJointAccelerationCommand_;
86 ros::ServiceServer ss_activateTasksAndConstraints_;
87 ros::ServiceServer ss_deactivateTasksAndConstraints_;
88 ros::ServiceServer ss_tasksAndConstraintsDeactivated_;
91 ros::Publisher desired_torque_pub_;
92 orca_ros::JointTorqueCommand trq_msg_;
94 bool robot_compensates_gravity_ =
false;
bool updateService(orca_ros::UpdateController::Request &req, orca_ros::UpdateController::Response &res)
Definition: RosController.cc:67
Definition: RosWrapperBase.h:50
bool printService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: RosController.cc:55
bool addTaskService(orca_ros::AddTask::Request &req, orca_ros::AddTask::Response &res)
Definition: RosController.cc:73
bool addConstraintService(orca_ros::AddConstraint::Request &req, orca_ros::AddConstraint::Response &res)
Definition: RosController.cc:83
bool getJointTorqueCommandService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res)
Definition: RosController.cc:99
Definition: RosCartesianAccelerationPID.h:42
virtual ~RosController()
Definition: RosController.cc:44
Definition: RosController.h:49
bool activateTasksAndConstraintsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: RosController.cc:111
bool deactivateTasksAndConstraintsService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: RosController.cc:117
bool getJointAccelerationCommandService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res)
Definition: RosController.cc:105
bool setPrintLevelService(orca_ros::SetInt::Request &req, orca_ros::SetInt::Response &res)
Definition: RosController.cc:61
bool tasksAndConstraintsDeactivatedService(orca_ros::GetBool::Request &req, orca_ros::GetBool::Response &res)
Definition: RosController.cc:123
RosController(const std::string &robot_name, std::shared_ptr< orca::optim::Controller > c, bool attach_torque_publish_callback=false)
Definition: RosController.cc:5
bool getNameService(orca_ros::GetString::Request &req, orca_ros::GetString::Response &res)
Definition: RosController.cc:49
bool getSolutionService(orca_ros::GetMatrix::Request &req, orca_ros::GetMatrix::Response &res)
Definition: RosController.cc:93