28 #include <control_msgs/FollowJointTrajectoryAction.h> 45 traj_client_ =
new TrajClient(
"r_arm_controller/joint_trajectory_action",
true);
50 ROS_INFO(
"Waiting for the joint_trajectory_action server");
86 control_msgs::FollowJointTrajectoryGoal goal;
89 goal.trajectory.joint_names.push_back(
"ffj0");
90 goal.trajectory.joint_names.push_back(
"lfj0");
93 goal.trajectory.points.resize(3);
98 goal.trajectory.points[ind].positions.resize(2);
99 goal.trajectory.points[ind].positions[0] = 0.0;
100 goal.trajectory.points[ind].positions[1] = 0.0;
106 goal.trajectory.points[ind].time_from_start =
ros::Duration(1.0);
110 goal.trajectory.points[ind].positions.resize(2);
111 goal.trajectory.points[ind].positions[0] = 1.0;
112 goal.trajectory.points[ind].positions[1] = 1.0;
113 goal.trajectory.points[ind].time_from_start =
ros::Duration(3.0);
117 goal.trajectory.points[ind].positions.resize(2);
118 goal.trajectory.points[ind].positions[0] = 0.0;
119 goal.trajectory.points[ind].positions[1] = 0.0;
120 goal.trajectory.points[ind].time_from_start =
ros::Duration(10.0);
128 control_msgs::FollowJointTrajectoryGoal goal;
130 goal.trajectory.joint_names.push_back(
"er");
131 goal.trajectory.joint_names.push_back(
"es");
133 goal.trajectory.points.resize(3);
136 goal.trajectory.points[ind].positions.resize(2);
137 goal.trajectory.points[ind].positions[0] = 0.0;
138 goal.trajectory.points[ind].positions[1] = 0.0;
139 goal.trajectory.points[ind].time_from_start =
ros::Duration(1.0);
142 goal.trajectory.points[ind].positions.resize(2);
143 goal.trajectory.points[ind].positions[0] = 1.0;
144 goal.trajectory.points[ind].positions[1] = 1.0;
145 goal.trajectory.points[ind].time_from_start =
ros::Duration(3.0);
148 goal.trajectory.points[ind].positions.resize(2);
149 goal.trajectory.points[ind].positions[0] = 0.0;
150 goal.trajectory.points[ind].positions[1] = 0.0;
151 goal.trajectory.points[ind].time_from_start =
ros::Duration(10.0);
163 int main(
int argc,
char **argv)
166 ros::init(argc, argv,
"shadow_trajectory_driver");
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
actionlib::SimpleClientGoalState getState()
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > TrajClient
void startTrajectory(control_msgs::FollowJointTrajectoryGoal goal)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
TrajClient * traj_client_
control_msgs::FollowJointTrajectoryGoal armWaveTrajectory()
SimpleClientGoalState getState() const
control_msgs::FollowJointTrajectoryGoal fingerWiggleTrajectory()