Go to the documentation of this file.00001
00013 #include "sr_mechanism_controllers/joint_trajectory_action_controller.hpp"
00014 #include <std_msgs/Float64.h>
00015 #include <boost/algorithm/string.hpp>
00016 #include <string>
00017
00018 namespace shadowrobot
00019 {
00020 JointTrajectoryActionController::JointTrajectoryActionController()
00021 {
00022 action_server = boost::shared_ptr<JTAS> (
00023 new JTAS("/r_arm_controller/joint_trajectory_action",
00024 boost::bind(&JointTrajectoryActionController::execute_trajectory, this, _1),
00025 false)
00026 );
00027
00028
00029
00030
00031
00032 std::string hand_names[] = {
00033 "ffj0", "ffj3", "ffj4",
00034 "lfj0", "lfj3", "lfj4", "lfj5",
00035 "mfj0", "mfj3", "mfj4",
00036 "rfj0", "rfj3", "rfj4",
00037 "thj1", "thj2", "thj3", "thj4", "thj5",
00038 "wrj1", "wrj2"
00039 };
00040 for (size_t i = 0; i < 20; i++)
00041 {
00042 joint_pub[hand_names[i]] = nh.advertise<std_msgs::Float64>(
00043 "/sh_"+hand_names[i]+"_mixed_position_velocity_controller/command", 2);
00044
00045 joint_pub[ boost::to_upper_copy(hand_names[i]) ] = nh.advertise<std_msgs::Float64>(
00046 "/sh_"+hand_names[i]+"_mixed_position_velocity_controller/command", 2);
00047 }
00048
00049
00050 std::string arm_names[] = {"sr", "ss", "es", "er"};
00051 for (size_t i = 0; i < 4; i++)
00052 {
00053 joint_pub[arm_names[i]] = nh.advertise<std_msgs::Float64>(
00054 "/sa_"+arm_names[i]+"_position_controller/command", 2);
00055 }
00056
00057
00058 std::string arm_names_2[] = {"ShoulderJRotate", "ShoulderJSwing", "ElbowJSwing", "ElbowJRotate"};
00059 for (size_t i = 0; i < 4; i++)
00060 {
00061 joint_pub[arm_names_2[i]] = nh.advertise<std_msgs::Float64>(
00062 "/sa_"+arm_names[i]+"_position_controller/command", 2);
00063 }
00064
00065 ROS_DEBUG("Starting JointTrajectoryActionController server");
00066 action_server->start();
00067 }
00068
00069 void JointTrajectoryActionController::execute_trajectory(
00070 const control_msgs::FollowJointTrajectoryGoalConstPtr& goal
00071 ){
00072 bool success = true;
00073 std::vector<std::string> joint_names = goal->trajectory.joint_names;
00074 JointTrajectoryPointVec trajectory_points = goal->trajectory.points;
00075 trajectory_msgs::JointTrajectoryPoint trajectory_step;
00076
00077
00078
00079
00080
00081
00082 ros::Duration sleeping_time(0.0), last_time(0.0);
00083 for(size_t index_step = 0; index_step < trajectory_points.size(); ++index_step)
00084 {
00085 trajectory_step = trajectory_points[index_step];
00086
00087
00088 if (action_server->isPreemptRequested() || !ros::ok())
00089 {
00090 ROS_INFO("Joint Trajectory Action Preempted");
00091 action_server->setPreempted();
00092 success = false;
00093 break;
00094 }
00095
00096
00097 for( size_t i = 0; i < joint_names.size(); i++ )
00098 {
00099 ROS_DEBUG_STREAM("trajectory: " << joint_names[i] << " " << trajectory_step.positions[i] << " / sleep: " << sleeping_time.toSec() );
00100 ros::Publisher pub = joint_pub[joint_names[i]];
00101 std_msgs::Float64 msg;
00102 msg.data = trajectory_step.positions[i];
00103 pub.publish(msg);
00104 }
00105
00106
00107
00108 sleeping_time = trajectory_step.time_from_start - last_time;
00109 sleeping_time.sleep();
00110 last_time = trajectory_step.time_from_start;
00111 }
00112
00113
00114 control_msgs::FollowJointTrajectoryResult joint_trajectory_result;
00115 if(success)
00116 action_server->setSucceeded(joint_trajectory_result);
00117 else
00118 action_server->setAborted(joint_trajectory_result);
00119 }
00120 }
00121
00122
00123 int main(int argc, char** argv)
00124 {
00125 ros::init(argc, argv, "sr_joint_trajectory_action_controller");
00126
00127 ros::AsyncSpinner spinner(1);
00128 spinner.start();
00129 shadowrobot::JointTrajectoryActionController jac;
00130 ros::spin();
00131
00132
00133 return 0;
00134 }
00135
00136
00137
00138
00139
00140
00141
00142