35 #ifndef ROS_CLIENT_HPP 36 #define ROS_CLIENT_HPP 39 #include <control_msgs/FollowJointTrajectoryAction.h> 40 #include <control_msgs/FollowJointTrajectoryActionGoal.h> 41 #include <control_msgs/FollowJointTrajectoryGoal.h> 42 #include <trajectory_msgs/JointTrajectoryPoint.h> 67 control_msgs::FollowJointTrajectoryGoal
goal;
71 "Your report to https://github.com/start-jsk/rtmros_hironx/issues " 72 "about the issue you are seeing is appreciated.")
76 explicit ROS_Client(std::vector<std::string> joingroups) :
78 "Your report to https://github.com/start-jsk/rtmros_hironx/issues " 79 "about the issue you are seeing is appreciated.")
107 static TrajClient aclient_larm(
"/larm_controller/joint_trajectory_action",
true);
108 static TrajClient aclient_rarm(
"/rarm_controller/joint_trajectory_action",
true);
109 static TrajClient aclient_head(
"/head_controller/joint_trajectory_action",
true);
110 static TrajClient aclient_torso(
"/torso_controller/joint_trajectory_action",
true);
114 goal_larm = control_msgs::FollowJointTrajectoryGoal();
116 goal_larm.trajectory.joint_names.push_back(
"LARM_JOINT0");
117 goal_larm.trajectory.joint_names.push_back(
"LARM_JOINT1");
118 goal_larm.trajectory.joint_names.push_back(
"LARM_JOINT2");
119 goal_larm.trajectory.joint_names.push_back(
"LARM_JOINT3");
120 goal_larm.trajectory.joint_names.push_back(
"LARM_JOINT4");
121 goal_larm.trajectory.joint_names.push_back(
"LARM_JOINT5");
125 goal_rarm = control_msgs::FollowJointTrajectoryGoal();
126 goal_rarm.trajectory.joint_names.push_back(
"RARM_JOINT0");
127 goal_rarm.trajectory.joint_names.push_back(
"RARM_JOINT1");
128 goal_rarm.trajectory.joint_names.push_back(
"RARM_JOINT2");
129 goal_rarm.trajectory.joint_names.push_back(
"RARM_JOINT3");
130 goal_rarm.trajectory.joint_names.push_back(
"RARM_JOINT4");
131 goal_rarm.trajectory.joint_names.push_back(
"RARM_JOINT5");
134 goal_head = control_msgs::FollowJointTrajectoryGoal();
135 goal_head.trajectory.joint_names.push_back(
"HEAD_JOINT0");
136 goal_head.trajectory.joint_names.push_back(
"HEAD_JOINT1");
139 goal_torso = control_msgs::FollowJointTrajectoryGoal();
140 goal_torso.trajectory.joint_names.push_back(
"CHEST_JOINT0");
144 std::cout <<
"Torso: [";
145 for (std::vector<std::string>::iterator
name =
goal_torso.trajectory.joint_names.begin();
147 std::cout << *
name <<
" ";
148 std::cout <<
"]\nHead: [";
149 for (std::vector<std::string>::iterator
name =
goal_head.trajectory.joint_names.begin();
151 std::cout << *
name <<
" ";
152 std::cout <<
"]\nL-Arm: [";
153 for (std::vector<std::string>::iterator
name =
goal_larm.trajectory.joint_names.begin();
155 std::cout << *
name <<
" ";
156 std::cout <<
"]\nR-Arm: [";
157 for (std::vector<std::string>::iterator
name =
goal_rarm.trajectory.joint_names.begin();
159 std::cout << *
name <<
" ";
160 std::cout <<
"]" << std::endl;
169 std::vector<double> POSITIONS_TORSO_DEG(1, 0.0);
172 std::vector<double> POSITIONS_HEAD_DEG(2, 0.0);
175 std::vector<double> POSITIONS_LARM_DEG(6);
176 POSITIONS_LARM_DEG[0] = 0.6;
177 POSITIONS_LARM_DEG[1] = 0.0;
178 POSITIONS_LARM_DEG[2] = -100;
179 POSITIONS_LARM_DEG[3] = -15.2;
180 POSITIONS_LARM_DEG[4] = 9.4;
181 POSITIONS_LARM_DEG[5] = -3.2;
184 std::vector<double> POSITIONS_RARM_DEG(6);
185 POSITIONS_RARM_DEG[0] = -0.6;
186 POSITIONS_RARM_DEG[1] = 0;
187 POSITIONS_RARM_DEG[2] = -100;
188 POSITIONS_RARM_DEG[3] = 15.2;
189 POSITIONS_RARM_DEG[4] = 9.4;
190 POSITIONS_RARM_DEG[5] = 3.2;
201 TrajClient* action_client;
205 action_client =
new TrajClient(
"torso_controller/joint_trajectory_action",
true);
210 action_client =
new TrajClient(
"head_controller/joint_trajectory_action",
true);
215 action_client =
new TrajClient(
"larm_controller/joint_trajectory_action",
true);
220 action_client =
new TrajClient(
"rarm_controller/joint_trajectory_action",
true);
226 trajectory_msgs::JointTrajectoryPoint pt;
227 pt.positions = positions_radian;
229 goal.trajectory.points.clear();
230 goal.trajectory.points.push_back(pt);
236 ROS_INFO(
"wait_for_result for the joint group %s = %d", groupname.c_str(), action_client->
waitForResult());
247 delete action_client;
251 void set_joint_angles_deg(std::string groupname, std::vector<double> positions_deg,
double duration = 7.0,
bool wait =
283 for (std::vector<std::string>::iterator
name = groupnames.begin();
name != groupnames.end(); ++
name)
284 std::cout << *
name <<
" ";
285 std::cout << std::endl;
287 GR_TORSO = groupnames[0];
288 GR_HEAD = groupnames[1];
289 GR_RARM = groupnames[2];
290 GR_LARM = groupnames[3];
297 std::vector<double> list_rad;
298 list_rad.reserve(list_degree.size());
299 for (std::vector<double>::iterator deg = list_degree.begin(); deg != list_degree.end(); ++deg)
301 double rad = *deg *
M_PI / 180.0;
302 list_rad.push_back(rad);
303 ROS_INFO(
"Position deg=%lf rad=%lf", *deg, rad);
std::vector< double > to_rad_list(std::vector< double > list_degree)
ROS_Client(const ROS_Client &obj)
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > TrajClient
void go_init(double task_duration=7.0)
control_msgs::FollowJointTrajectoryGoal goal_head
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
control_msgs::FollowJointTrajectoryGoal goal_rarm
void set_joint_angles_rad(std::string groupname, std::vector< double > positions_radian, double duration=7.0, bool wait=false)
ROS_Client & operator=(const ROS_Client &obj)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
void set_groupnames(std::vector< std::string > groupnames)
control_msgs::FollowJointTrajectoryGoal goal_torso
void set_joint_angles_deg(std::string groupname, std::vector< double > positions_deg, double duration=7.0, bool wait=false)
void init_action_clients()
control_msgs::FollowJointTrajectoryGoal goal
ROS_Client(std::vector< std::string > joingroups)
control_msgs::FollowJointTrajectoryGoal goal_larm
const std::string MSG_ASK_ISSUEREPORT