29 #include <std_msgs/Float64.h> 30 #include <boost/algorithm/string.hpp> 39 new JTAS(
"/r_arm_controller/joint_trajectory_action",
47 std::string hand_names[] =
49 "ffj0",
"ffj3",
"ffj4",
50 "lfj0",
"lfj3",
"lfj4",
"lfj5",
51 "mfj0",
"mfj3",
"mfj4",
52 "rfj0",
"rfj3",
"rfj4",
53 "thj1",
"thj2",
"thj3",
"thj4",
"thj5",
56 for (
size_t i = 0; i < 20; i++)
59 "/sh_" + hand_names[i] +
"_mixed_position_velocity_controller/command", 2);
62 "/sh_" + hand_names[i] +
"_mixed_position_velocity_controller/command", 2);
66 std::string arm_names[] = {
"sr",
"ss",
"es",
"er"};
67 for (
size_t i = 0; i < 4; i++)
70 "/sa_" + arm_names[i] +
"_position_controller/command", 2);
74 std::string arm_names_2[] = {
"ShoulderJRotate",
"ShoulderJSwing",
"ElbowJSwing",
"ElbowJRotate"};
75 for (
size_t i = 0; i < 4; i++)
78 "/sa_" + arm_names[i] +
"_position_controller/command", 2);
81 ROS_DEBUG(
"Starting JointTrajectoryActionController server");
86 const control_msgs::FollowJointTrajectoryGoalConstPtr &goal
90 std::vector<std::string>
joint_names = goal->trajectory.joint_names;
92 trajectory_msgs::JointTrajectoryPoint trajectory_step;
100 for (
size_t index_step = 0; index_step < trajectory_points.size(); ++index_step)
102 trajectory_step = trajectory_points[index_step];
107 ROS_INFO(
"Joint Trajectory Action Preempted");
114 for (
size_t i = 0; i < joint_names.size(); i++)
116 ROS_DEBUG_STREAM(
"trajectory: " << joint_names[i] <<
" " << trajectory_step.positions[i] <<
" / sleep: " <<
117 sleeping_time.toSec());
119 std_msgs::Float64 msg;
120 msg.data = trajectory_step.positions[i];
126 sleeping_time = trajectory_step.time_from_start - last_time;
127 sleeping_time.sleep();
128 last_time = trajectory_step.time_from_start;
132 control_msgs::FollowJointTrajectoryResult joint_trajectory_result;
145 int main(
int argc,
char **argv)
147 ros::init(argc, argv,
"sr_joint_trajectory_action_controller");
std::vector< trajectory_msgs::JointTrajectoryPoint > JointTrajectoryPointVec
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
actionlib::SimpleActionServer< control_msgs::FollowJointTrajectoryAction > JTAS
ROSCPP_DECL void spin(Spinner &spinner)
JointTrajectoryActionController()
Implement an actionlib server to execute a control_msgs::JointTrajectoryAction. Follows the given tra...
boost::shared_ptr< JTAS > action_server
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_DEBUG_STREAM(args)
void execute_trajectory(const control_msgs::FollowJointTrajectoryGoalConstPtr &goal)