50 const std::string& controller_name);
57 void update(
double current_time,
double dt);
58 bool addTask(orca_ros::TaskDescription td);
69 ros::ServiceClient sc_getName_;
70 ros::ServiceClient sc_print_;
71 ros::ServiceClient sc_setPrintLevel_;
72 ros::ServiceClient sc_update_;
73 ros::ServiceClient sc_addTask_;
74 ros::ServiceClient sc_addConstraint_;
75 ros::ServiceClient sc_getFullSolution_;
76 ros::ServiceClient sc_getJointTorqueCommand_;
77 ros::ServiceClient sc_getJointAccelerationCommand_;
78 ros::ServiceClient sc_activateTasksAndConstraints_;
79 ros::ServiceClient sc_deactivateTasksAndConstraints_;
80 ros::ServiceClient sc_tasksAndConstraintsDeactivated_;
virtual ~RosControllerProxy()
Definition: RosControllerProxy.cc:23
std::string getName()
Definition: RosControllerProxy.cc:28
Definition: RosWrapperBase.h:50
Eigen::VectorXd getJointAccelerationCommand()
Definition: RosControllerProxy.cc:110
bool addTask(orca_ros::TaskDescription td)
Definition: RosControllerProxy.cc:68
bool tasksAndConstraintsDeactivated()
Definition: RosControllerProxy.cc:140
RosControllerProxy(const std::string &robot_name, const std::string &controller_name)
Definition: RosControllerProxy.cc:5
void update(double current_time, double dt)
Definition: RosControllerProxy.cc:57
void deactivateTasksAndConstraints()
Definition: RosControllerProxy.cc:131
void activateTasksAndConstraints()
Definition: RosControllerProxy.cc:122
Definition: RosCartesianAccelerationPID.h:42
Definition: RosControllerProxy.h:46
bool addConstraint(orca_ros::ConstraintDescription cd)
Definition: RosControllerProxy.cc:77
Eigen::VectorXd getFullSolution()
Definition: RosControllerProxy.cc:86
void print()
Definition: RosControllerProxy.cc:38
void setPrintLevel(int level)
Definition: RosControllerProxy.cc:47
Eigen::VectorXd getJointTorqueCommand()
Definition: RosControllerProxy.cc:98