min_max_trajectory.cpp
Go to the documentation of this file.
1 #include <ros/ros.h>
2 #include <control_msgs/FollowJointTrajectoryAction.h>
4 
6 
7 static const double MIN_POSITIONS [5] = {-3.025528, -0.135228, -1.0, -2.033309, -2.993240};
8 static const double MAX_POSITIONS [5] = {2.891097, 2.168572, 2.054223, 1.876133, 2.870985};
9 
10 static const size_t NUM_TRAJ_POINTS = 7;
11 static const size_t NUM_JOINTS = 5;
12 
13 class RobotArm
14 {
15 private:
16 
17  // Action client for the joint trajectory action
18  // used to trigger the arm movement action
20 
21 public:
24  {
25  // tell the action client that we want to spin a thread by default
26  traj_client_ = new TrajClient("katana_arm_controller/follow_joint_trajectory", true);
27 
28  // wait for action server to come up
29  while (!traj_client_->waitForServer(ros::Duration(5.0)) && ros::ok())
30  {
31  ROS_INFO("Waiting for the follow_joint_trajectory server");
32  }
33  }
34 
37  {
38  delete traj_client_;
39  }
40 
42  void startTrajectory(control_msgs::FollowJointTrajectoryGoal goal)
43  {
44  // When to start the trajectory: 1s from now
45  goal.trajectory.header.stamp = ros::Time::now() + ros::Duration(1.0);
46  traj_client_->sendGoal(goal);
47  }
48 
49  control_msgs::FollowJointTrajectoryGoal armExtensionTrajectory(size_t moving_joint)
50  {
51  //our goal variable
52  control_msgs::FollowJointTrajectoryGoal goal;
53 
54  // First, the joint names, which apply to all waypoints
55  goal.trajectory.joint_names.push_back("katana_motor1_pan_joint");
56  goal.trajectory.joint_names.push_back("katana_motor2_lift_joint");
57  goal.trajectory.joint_names.push_back("katana_motor3_lift_joint");
58  goal.trajectory.joint_names.push_back("katana_motor4_lift_joint");
59  goal.trajectory.joint_names.push_back("katana_motor5_wrist_roll_joint");
60 
61  goal.trajectory.points.resize(NUM_TRAJ_POINTS);
62 
63  // First trajectory point (should be equal to current position of joints)
64  size_t seg = 0;
65  goal.trajectory.points[seg].positions.resize(NUM_JOINTS);
66  goal.trajectory.points[seg].velocities.resize(NUM_JOINTS);
67  for (size_t j = 0; j < NUM_JOINTS; ++j)
68  {
69  goal.trajectory.points[seg].positions[j] = 0.0;
70  goal.trajectory.points[seg].velocities[j] = 0.0;
71  }
72 
73  // Remaining trajectory points
74  for (size_t seg = 1; seg < NUM_TRAJ_POINTS; seg++)
75  {
76  goal.trajectory.points[seg].positions.resize(NUM_JOINTS);
77  goal.trajectory.points[seg].velocities.resize(NUM_JOINTS);
78  for (size_t j = 0; j < NUM_JOINTS; ++j)
79  {
80  goal.trajectory.points[seg].positions[j] = goal.trajectory.points[seg - 1].positions[j];
81  goal.trajectory.points[seg].velocities[j] = 0.0;
82  }
83  }
84 
85  // overwrite with the positions for the moving joint
86  // move to min, hold it there, move to max, hold it there, move to 0, hold it there
87  assert(NUM_TRAJ_POINTS == 7);
88  goal.trajectory.points[0].positions[moving_joint] = 0.0;
89  goal.trajectory.points[0].time_from_start = ros::Duration(0.0);
90 
91  goal.trajectory.points[1].positions[moving_joint] = MIN_POSITIONS[moving_joint];
92  goal.trajectory.points[1].time_from_start = ros::Duration(2.5);
93 
94  goal.trajectory.points[2].positions[moving_joint] = MIN_POSITIONS[moving_joint];
95  goal.trajectory.points[2].time_from_start = ros::Duration(5.5);
96 
97  goal.trajectory.points[3].positions[moving_joint] = MAX_POSITIONS[moving_joint];
98  goal.trajectory.points[3].time_from_start = ros::Duration(10.5);
99 
100  goal.trajectory.points[4].positions[moving_joint] = MAX_POSITIONS[moving_joint];
101  goal.trajectory.points[4].time_from_start = ros::Duration(13.5);
102 
103  goal.trajectory.points[5].positions[moving_joint] = 0.0;
104  goal.trajectory.points[5].time_from_start = ros::Duration(16.0);
105 
106  goal.trajectory.points[6].positions[moving_joint] = 0.0;
107  goal.trajectory.points[6].time_from_start = ros::Duration(19.0);
108 
109  //we are done; return the goal
110  return goal;
111  }
112 
115  {
116  return traj_client_->getState();
117  }
118 
119 };
120 
121 int main(int argc, char** argv)
122 {
123  // Init the ROS node
124  ros::init(argc, argv, "min_max_trajectory");
125 
126  RobotArm arm;
127  while (ros::ok())
128  {
129  for (size_t joint = 0; joint < NUM_JOINTS; joint++)
130  {
131  // Start the trajectory
132  arm.startTrajectory(arm.armExtensionTrajectory(joint));
133  // Wait for trajectory completion
134  while (!arm.getState().isDone() && ros::ok())
135  {
136  usleep(50000);
137  }
138  }
139  }
140 
141 }
142 
static const size_t NUM_TRAJ_POINTS
void startTrajectory(control_msgs::FollowJointTrajectoryGoal goal)
Sends the command to start a given trajectory.
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
~RobotArm()
Clean up the action client.
static const double MIN_POSITIONS[5]
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > TrajClient
static const size_t NUM_JOINTS
int main(int argc, char **argv)
static const double MAX_POSITIONS[5]
TrajClient * traj_client_
#define ROS_INFO(...)
ROSCPP_DECL bool ok()
control_msgs::FollowJointTrajectoryGoal armExtensionTrajectory(size_t moving_joint)
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
RobotArm()
Initialize the action client and wait for action server to come up.
actionlib::SimpleClientGoalState getState()
Returns the current state of the action.
static Time now()
SimpleClientGoalState getState() const


katana_arm_gazebo
Author(s): Martin Günther
autogenerated on Fri Jun 7 2019 22:06:38