simple_trajectory.cpp
Go to the documentation of this file.
1 
27 #include <ros/ros.h>
28 #include <control_msgs/FollowJointTrajectoryAction.h>
30 
32 
33 class ShadowTrajectory
34 {
35 private:
36  // Action client for the joint trajectory action
37  // used to trigger the arm movement action
39 
40 public:
41  // ! Initialize the action client and wait for action server to come up
43  {
44  // tell the action client that we want to spin a thread by default
45  traj_client_ = new TrajClient("r_arm_controller/joint_trajectory_action", true);
46 
47  // wait for action server to come up
48  while (!traj_client_->waitForServer(ros::Duration(5.0)))
49  {
50  ROS_INFO("Waiting for the joint_trajectory_action server");
51  }
52  }
53 
54  // ! Clean up the action client
56  {
57  delete traj_client_;
58  }
59 
60  // ! Sends the command to start a given trajectory
61  void startTrajectory(control_msgs::FollowJointTrajectoryGoal goal)
62  {
63  // When to start the trajectory: 1s from now
64  goal.trajectory.header.stamp = ros::Time::now() + ros::Duration(1.0);
65  traj_client_->sendGoal(goal);
66  }
67 
68  // ! Wait for currently running trajectory to finish
70  {
71  while (!getState().isDone() && ros::ok())
72  {
73  usleep(50000);
74  }
75  }
76 
77  // ! Generates a simple trajectory to move two fingers on the hand.
83  control_msgs::FollowJointTrajectoryGoal fingerWiggleTrajectory()
84  {
85  // our goal variable
86  control_msgs::FollowJointTrajectoryGoal goal;
87 
88  // First, the joint names, which apply to all waypoints
89  goal.trajectory.joint_names.push_back("ffj0");
90  goal.trajectory.joint_names.push_back("lfj0");
91 
92  // Set number of waypoints in this goal trajectory
93  goal.trajectory.points.resize(3);
94 
95  // First trajectory point
96  // Positions
97  int ind = 0;
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;
101  // Points also have velocities, but the shadow action server doesn't use them
102  // goal.trajectory.points[ind].velocities.resize(2);
103  // goal.trajectory.points[ind].velocities[0] = 0.0;
104  // goal.trajectory.points[ind].velocities[0] = 0.0;
105  // To be reached 1.0 second after starting along the trajectory
106  goal.trajectory.points[ind].time_from_start = ros::Duration(1.0);
107 
108  // 2nd trajectory point
109  ind += 1;
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);
114 
115  // 3rd trajectory point
116  ind += 1;
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);
121 
122  return goal;
123  }
124 
125  // ! Generates a simple trajectory to move the arm
126  control_msgs::FollowJointTrajectoryGoal armWaveTrajectory()
127  {
128  control_msgs::FollowJointTrajectoryGoal goal;
129 
130  goal.trajectory.joint_names.push_back("er");
131  goal.trajectory.joint_names.push_back("es");
132 
133  goal.trajectory.points.resize(3);
134 
135  int ind = 0;
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);
140 
141  ind += 1;
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);
146 
147  ind += 1;
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);
152 
153  return goal;
154  }
155 
156  // ! Returns the current state of the action
158  {
159  return traj_client_->getState();
160  }
161 };
162 
163 int main(int argc, char **argv)
164 {
165  // Init the ROS node
166  ros::init(argc, argv, "shadow_trajectory_driver");
167 
168  ShadowTrajectory sj;
170  sj.waitTrajectory();
171 
173  sj.waitTrajectory();
174 }
175 
176 // vim: sw=2:ts=2
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
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
void startTrajectory(control_msgs::FollowJointTrajectoryGoal goal)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
control_msgs::FollowJointTrajectoryGoal armWaveTrajectory()
static Time now()
SimpleClientGoalState getState() const
control_msgs::FollowJointTrajectoryGoal fingerWiggleTrajectory()


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:58