Go to the documentation of this file.00001 #ifndef ROS_CLIENT_HPP
00002 #define ROS_CLIENT_HPP
00003
00004 #include <ros/ros.h>
00005 #include <pr2_controllers_msgs/JointTrajectoryAction.h>
00006 #include <pr2_controllers_msgs/JointTrajectoryActionGoal.h>
00007 #include <pr2_controllers_msgs/JointTrajectoryGoal.h>
00008 #include <trajectory_msgs/JointTrajectoryPoint.h>
00009 #include <actionlib/client/simple_action_client.h>
00010 #include <string>
00011 #include <vector>
00012 #include <cmath>
00013
00014 class ROS_Client {
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029 public:
00030 typedef actionlib::SimpleActionClient< pr2_controllers_msgs::JointTrajectoryAction > TrajClient;
00031
00032 pr2_controllers_msgs::JointTrajectoryGoal goal;
00033
00034 ROS_Client():
00035 GR_TORSO("torso"),GR_HEAD("head"),
00036 GR_LARM("larm"),GR_RARM("rarm"),
00037 MSG_ASK_ISSUEREPORT("Your report to https://github.com/start-jsk/rtmros_hironx/issues about the issue you are seeing is appreciated.")
00038 {};
00039
00040 explicit ROS_Client(std::vector<std::string> joingroups):
00041 MSG_ASK_ISSUEREPORT("Your report to https://github.com/start-jsk/rtmros_hironx/issues about the issue you are seeing is appreciated.")
00042 {
00043 set_groupnames(joingroups);
00044 };
00045
00046 ROS_Client(const ROS_Client& obj)
00047 {
00048 GR_TORSO = obj.GR_TORSO;
00049 GR_HEAD = obj.GR_HEAD;
00050 GR_LARM = obj.GR_LARM;
00051 GR_RARM = obj.GR_RARM;
00052 };
00053
00054 ROS_Client& operator=(const ROS_Client& obj)
00055 {
00056 GR_TORSO= obj.GR_TORSO;
00057 GR_HEAD = obj.GR_HEAD;
00058 GR_LARM = obj.GR_LARM;
00059 GR_RARM = obj.GR_RARM;
00060 return *this;
00061 };
00062
00063 ~ROS_Client(){};
00064
00065 void init_action_clients()
00066 {
00067 static TrajClient aclient_larm("/larm_controller/joint_trajectory_action", true);
00068 static TrajClient aclient_rarm("/rarm_controller/joint_trajectory_action", true);
00069 static TrajClient aclient_head("/head_controller/joint_trajectory_action", true);
00070 static TrajClient aclient_torso("/torso_controller/joint_trajectory_action",true);
00071
00072 aclient_larm.waitForServer();
00073 ROS_INFO("ros_client; 1");
00074 goal_larm = pr2_controllers_msgs::JointTrajectoryGoal();
00075 ROS_INFO("ros_client; 2");
00076 goal_larm.trajectory.joint_names.push_back("LARM_JOINT0");
00077 goal_larm.trajectory.joint_names.push_back("LARM_JOINT1");
00078 goal_larm.trajectory.joint_names.push_back("LARM_JOINT2");
00079 goal_larm.trajectory.joint_names.push_back("LARM_JOINT3");
00080 goal_larm.trajectory.joint_names.push_back("LARM_JOINT4");
00081 goal_larm.trajectory.joint_names.push_back("LARM_JOINT5");
00082 ROS_INFO("ros_client; 3");
00083
00084 aclient_rarm.waitForServer();
00085 goal_rarm = pr2_controllers_msgs::JointTrajectoryGoal();
00086 goal_rarm.trajectory.joint_names.push_back("RARM_JOINT0");
00087 goal_rarm.trajectory.joint_names.push_back("RARM_JOINT1");
00088 goal_rarm.trajectory.joint_names.push_back("RARM_JOINT2");
00089 goal_rarm.trajectory.joint_names.push_back("RARM_JOINT3");
00090 goal_rarm.trajectory.joint_names.push_back("RARM_JOINT4");
00091 goal_rarm.trajectory.joint_names.push_back("RARM_JOINT5");
00092
00093 aclient_head.waitForServer();
00094 goal_head = pr2_controllers_msgs::JointTrajectoryGoal();
00095 goal_head.trajectory.joint_names.push_back("HEAD_JOINT0");
00096 goal_head.trajectory.joint_names.push_back("HEAD_JOINT1");
00097
00098 aclient_torso.waitForServer();
00099 goal_torso = pr2_controllers_msgs::JointTrajectoryGoal();
00100 goal_torso.trajectory.joint_names.push_back("CHEST_JOINT0");
00101
00102
00103 ROS_INFO("\nJoint names;");
00104 std::cout << "Torso: [";
00105 for(std::vector<std::string>::iterator name = goal_torso.trajectory.joint_names.begin();
00106 name != goal_torso.trajectory.joint_names.end(); ++name)
00107 std::cout << *name << " ";
00108 std::cout << "]\nHead: [";
00109 for(std::vector<std::string>::iterator name = goal_head.trajectory.joint_names.begin();
00110 name != goal_head.trajectory.joint_names.end(); ++name)
00111 std::cout << *name << " ";
00112 std::cout << "]\nL-Arm: [";
00113 for(std::vector<std::string>::iterator name = goal_larm.trajectory.joint_names.begin();
00114 name != goal_larm.trajectory.joint_names.end(); ++name)
00115 std::cout << *name << " ";
00116 std::cout << "]\nR-Arm: [";
00117 for(std::vector<std::string>::iterator name = goal_rarm.trajectory.joint_names.begin();
00118 name != goal_rarm.trajectory.joint_names.end(); ++name)
00119 std::cout << *name << " "; std::cout << "]" << std::endl;
00120 }
00121
00122
00123
00124
00125
00126 void go_init(double task_duration=7.0)
00127 {
00128 ROS_INFO("*** go_init begins ***");
00129 std::vector<double> POSITIONS_TORSO_DEG(1,0.0);
00130 set_joint_angles_deg(GR_TORSO, POSITIONS_TORSO_DEG, task_duration);
00131
00132 std::vector<double> POSITIONS_HEAD_DEG(2,0.0);
00133 set_joint_angles_deg(GR_HEAD, POSITIONS_HEAD_DEG, task_duration);
00134
00135 std::vector<double> POSITIONS_LARM_DEG(6);
00136 POSITIONS_LARM_DEG[0] = 0.6;
00137 POSITIONS_LARM_DEG[1] = 0.0;
00138 POSITIONS_LARM_DEG[2] =-100;
00139 POSITIONS_LARM_DEG[3] =-15.2;
00140 POSITIONS_LARM_DEG[4] = 9.4;
00141 POSITIONS_LARM_DEG[5] =-3.2;
00142 set_joint_angles_deg(GR_LARM, POSITIONS_LARM_DEG, task_duration);
00143
00144 std::vector<double> POSITIONS_RARM_DEG(6);
00145 POSITIONS_RARM_DEG[0] =-0.6;
00146 POSITIONS_RARM_DEG[1] = 0;
00147 POSITIONS_RARM_DEG[2] =-100;
00148 POSITIONS_RARM_DEG[3] =15.2;
00149 POSITIONS_RARM_DEG[4] = 9.4;
00150 POSITIONS_RARM_DEG[5] = 3.2;
00151 set_joint_angles_deg(GR_RARM, POSITIONS_RARM_DEG,task_duration, true);
00152
00153 ROS_INFO("*** go_init_ends ***");
00154 }
00155
00156
00157
00158 void set_joint_angles_rad(std::string groupname,
00159 std::vector<double> positions_radian,
00160 double duration=7.0,
00161 bool wait=false)
00162 {
00163 TrajClient* action_client;
00164
00165 if(groupname == GR_TORSO){
00166 action_client = new TrajClient("torso_controller/joint_trajectory_action", true);
00167 goal = goal_torso;
00168 }
00169 else if(groupname == GR_HEAD){
00170 action_client = new TrajClient("head_controller/joint_trajectory_action", true);
00171 goal = goal_head;
00172 }
00173 else if(groupname == GR_LARM){
00174 action_client = new TrajClient("larm_controller/joint_trajectory_action", true);
00175 goal = goal_larm;
00176 }
00177 else if(groupname == GR_RARM){
00178 action_client = new TrajClient("rarm_controller/joint_trajectory_action", true);
00179 goal = goal_rarm;
00180 }
00181
00182 try {
00183 trajectory_msgs::JointTrajectoryPoint pt;
00184 pt.positions = positions_radian;
00185 pt.time_from_start = ros::Duration(duration);
00186 goal.trajectory.points.clear();
00187 goal.trajectory.points.push_back(pt);
00188 goal.trajectory.header.stamp = ros::Time::now() + ros::Duration(duration);
00189 action_client->sendGoal(goal);
00190 if(wait){
00191 ROS_INFO("waiting......");
00192 ROS_INFO("wait_for_result for the joint group %s = %d",
00193 groupname.c_str(), action_client->waitForResult());
00194 }
00195 }
00196 catch(const ros::Exception& e){
00197 ROS_INFO("%s",e.what());
00198 }
00199 catch( ... ){
00200 ROS_INFO("Exception");
00201 }
00202 delete action_client;
00203 }
00204
00205
00206
00207 void set_joint_angles_deg(std::string groupname,
00208 std::vector<double> positions_deg,
00209 double duration = 7.0,
00210 bool wait = false)
00211 {
00212 set_joint_angles_rad(groupname,to_rad_list(positions_deg),duration,wait);
00213 }
00214
00215 private:
00216 std::string GR_TORSO;
00217 std::string GR_HEAD;
00218 std::string GR_LARM;
00219 std::string GR_RARM;
00220
00221 const std::string MSG_ASK_ISSUEREPORT;
00222
00223 pr2_controllers_msgs::JointTrajectoryGoal goal_larm;
00224 pr2_controllers_msgs::JointTrajectoryGoal goal_rarm;
00225 pr2_controllers_msgs::JointTrajectoryGoal goal_head;
00226 pr2_controllers_msgs::JointTrajectoryGoal goal_torso;
00227
00228
00229
00230
00231
00232
00233
00234
00235
00236
00237 void set_groupnames(std::vector<std::string> groupnames)
00238 {
00239
00240 ROS_INFO("set_groupnames");
00241 for(std::vector<std::string>::iterator name = groupnames.begin(); name != groupnames.end(); ++name)
00242 std::cout << *name << " "; std::cout << std::endl;
00243
00244 GR_TORSO = groupnames[0];
00245 GR_HEAD = groupnames[1];
00246 GR_RARM = groupnames[2];
00247 GR_LARM = groupnames[3];
00248 }
00249
00250
00251
00252 std::vector<double> to_rad_list(std::vector<double> list_degree)
00253 {
00254 std::vector<double> list_rad;
00255 list_rad.reserve(list_degree.size());
00256 for(std::vector<double>::iterator deg = list_degree.begin(); deg != list_degree.end(); ++deg){
00257 double rad = *deg * M_PI / 180.0;
00258 list_rad.push_back(rad);
00259 ROS_INFO("Position deg=%lf rad=%lf", *deg, rad);
00260 }
00261 return list_rad;
00262 }
00263
00264 };
00265
00266 #endif