2 #include "sensor_msgs/JointState.h" 3 #include "hebiros/AddGroupFromNamesSrv.h" 16 int main(
int argc,
char **argv) {
19 ros::init(argc, argv,
"example_03_command_node");
23 std::string group_name =
"my_group";
27 "/hebiros/add_group_from_names");
36 "/hebiros/"+group_name+
"/command/joint_state", 100);
38 AddGroupFromNamesSrv add_group_srv;
41 add_group_srv.request.group_name = group_name;
42 add_group_srv.request.names = {
"base",
"shoulder",
"elbow"};
43 add_group_srv.request.families = {
"HEBI"};
46 while(!add_group_client.
call(add_group_srv)) {}
50 sensor_msgs::JointState command_msg;
51 command_msg.name.push_back(
"HEBI/base");
52 command_msg.name.push_back(
"HEBI/shoulder");
53 command_msg.name.push_back(
"HEBI/elbow");
55 command_msg.effort.resize(3);
59 double spring_constant = -10;
64 command_msg.effort[0] = spring_constant *
feedback.position[0];
65 command_msg.effort[1] = spring_constant *
feedback.position[1];
66 command_msg.effort[2] = spring_constant *
feedback.position[2];
67 command_publisher.
publish(command_msg);
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
sensor_msgs::JointState feedback
int main(int argc, char **argv)
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void feedback_callback(sensor_msgs::JointState data)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spinOnce()