36 #include <manipulation_msgs/JointTraj.h> 50 ros::Node *node =
new ros::Node(
"test_arm_trajectory_controller");
58 manipulation_msgs::JointTraj
cmd;
63 cmd.set_points_size(num_points);
65 for(
int i=0; i<num_points; i++)
67 cmd.points[i].set_positions_size(num_joints);
68 for(
int j=0; j < num_joints; j++)
70 cmd.points[i].positions[j] = 0.0;
85 cmd.points[0].positions[0] = 0.5;
86 cmd.points[0].positions[1] = 0.5;
87 cmd.points[0].positions[2] = 0.2;
88 cmd.points[0].positions[3] = -0.5;
89 cmd.points[0].positions[4] = 0.4;
90 cmd.points[0].positions[5] = 0.0;
91 cmd.points[0].positions[6] = 0.0;
92 cmd.points[0].time = 0.0;
94 cmd.points[1].positions[0] = 0.0;
95 cmd.points[1].positions[1] = 0.0;
96 cmd.points[1].positions[2] = 0.0;
97 cmd.points[1].positions[3] = 0.0;
98 cmd.points[1].positions[4] = 0.0;
99 cmd.points[1].positions[5] = 0.0;
100 cmd.points[1].positions[6] = 0.0;
101 cmd.points[1].time = 0.0;
103 cmd.points[2].positions[0] = -0.5;
104 cmd.points[2].positions[1] = 0.3;
105 cmd.points[2].positions[2] = 0.2;
106 cmd.points[2].positions[3] = -1.0;
107 cmd.points[2].positions[4] = -0.4;
108 cmd.points[2].positions[5] = 0.0;
109 cmd.points[2].positions[6] = 0.0;
110 cmd.points[2].time = 0.0;
112 node->advertise<manipulation_msgs::JointTraj>(
"/arm/trajectory_controller/arm_trajectory_command",1);
113 node->publish(
"/arm/trajectory_controller/arm_trajectory_command",cmd);
void finalize(int donecare)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
Duration & fromSec(double t)