test_trajectory.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, University of Colorado, Boulder
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Univ of CO, Boulder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Dave Coleman <dave@dav.ee>
36  Desc: Generate a random trajectory to test the ros_control controller
37 */
38 
39 // ROS
40 #include <ros/ros.h>
41 #include <control_msgs/FollowJointTrajectoryAction.h>
42 #include <trajectory_msgs/JointTrajectory.h>
45 
47 {
48 static const double SEC_PER_TRAJ_POINT = 5.0; // time between points
49 static const std::size_t TRAJ_POINTS = 10; // number of points to generate
50 
52 {
53 public:
58  {
59  nh_private_.getParam("trajectory_controller", trajectory_controller);
60  if (trajectory_controller.empty())
61  {
62  ROS_FATAL_STREAM_NAMED("test_trajectory",
63  "No joint trajectory controller parameter found on the parameter server");
64  exit(-1);
65  }
66  ROS_INFO_STREAM_NAMED("test_trajectory", "Connecting to controller " << trajectory_controller);
67 
68  // create the action client
69  // true causes the client to spin its own thread
71  trajectory_controller + "/follow_joint_trajectory/", true);
72 
73  ROS_INFO_NAMED("test_trajetory", "Waiting for action server to start.");
74  // wait for the action server to start
75  action_client.waitForServer(); // will wait for infinite time
76 
77  ROS_INFO_NAMED("test_trajetory", "Action server started, sending goal.");
78 
79  // send a goal to the action
80  control_msgs::FollowJointTrajectoryGoal goal;
81  goal.trajectory = createTrajectory();
82  std::cout << "Trajectry:\n" << goal.trajectory << std::endl;
83  action_client.sendGoal(goal);
84 
85  // Wait for the action to return
86  double wait_extra_padding = 2; // time to wait longer than trajectory itself
87  bool finished_before_timeout = action_client.waitForResult(
88  ros::Duration(goal.trajectory.points.back().time_from_start.toSec() + wait_extra_padding));
89 
90  if (finished_before_timeout)
91  {
92  actionlib::SimpleClientGoalState state = action_client.getState();
93  ROS_INFO_NAMED("test_trajetory", "Action finished: %s", state.toString().c_str());
94  }
95  else
96  ROS_INFO_NAMED("test_trajetory", "Action did not finish before the time out.");
97 
98  ROS_INFO_STREAM_NAMED("test_trajectory", "TestTrajectory Finished");
99  }
100 
104  trajectory_msgs::JointTrajectory createTrajectory()
105  {
106  std::vector<std::string> joint_names;
107  double min_joint_value = -3.14;
108  double max_joint_value = 3.14;
109 
110  // Get joint names
111  nh_private_.getParam(trajectory_controller + "/joints", joint_names);
112  if (joint_names.size() == 0)
113  {
114  ROS_FATAL_STREAM_NAMED("init",
115  "Not joints found on parameter server for controller, did you load the proper yaml file?"
116  << " Namespace: " << nh_private_.getNamespace() << "/hardware_interface/joints");
117  exit(-1);
118  }
119 
120  nh_private_.getParam("min_joint_value", min_joint_value);
121  nh_private_.getParam("max_joint_value", max_joint_value);
122  ROS_DEBUG_STREAM_NAMED("test_trajectory", "Creating trajectory with joint values from " << min_joint_value << " to "
123  << max_joint_value);
124 
125  // Create header
126  trajectory_msgs::JointTrajectory trajectory;
127  trajectory.header.stamp = ros::Time::now();
128  trajectory.joint_names = joint_names;
129 
130  // Create trajectory with x points
131  trajectory.points.resize(TRAJ_POINTS);
132  for (std::size_t i = 0; i < TRAJ_POINTS; ++i)
133  {
134  trajectory.points[i].positions.resize(joint_names.size());
135  // for each joint
136  for (std::size_t j = 0; j < joint_names.size(); ++j)
137  {
138  trajectory.points[i].positions[j] = dRand(min_joint_value, max_joint_value);
139  trajectory.points[i].time_from_start = ros::Duration(i * SEC_PER_TRAJ_POINT);
140  }
141  }
142 
143  return trajectory;
144  }
145 
147  double dRand(double dMin, double dMax)
148  {
149  double d = (double)rand() / RAND_MAX;
150  return dMin + d * (dMax - dMin);
151  }
152 
153 private:
154  // A shared node handle
156 
157  // A string containing the 'trajectory_controller' parameter value
159 }; // end class
160 
161 // Create boost pointers for this class
164 
165 } // namespace ros_control_boilerplate
166 
167 int main(int argc, char** argv)
168 {
169  ros::init(argc, argv, "test_trajectory");
170  ROS_INFO_STREAM_NAMED("test_trajectory", "Starting TestTrajectory...");
171 
172  // Allow the action server to recieve and send ros messages
174  spinner.start();
175 
177 
178  ROS_INFO_STREAM_NAMED("test_trajectory", "Shutting down.");
179  ros::shutdown();
180 
181  return 0;
182 }
d
static const double SEC_PER_TRAJ_POINT
#define ROS_INFO_NAMED(name,...)
boost::shared_ptr< TestTrajectory > TestTrajectoryPtr
trajectory_msgs::JointTrajectory createTrajectory()
Create random trajectory.
#define ROS_DEBUG_STREAM_NAMED(name, args)
int main(int argc, char **argv)
double dRand(double dMin, double dMax)
Get random number.
bool waitForResult(const ros::Duration &timeout=ros::Duration(0, 0))
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::string toString() const
#define ROS_INFO_STREAM_NAMED(name, args)
void spinner()
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
SimpleClientGoalState getState() const
#define ROS_FATAL_STREAM_NAMED(name, args)
bool getParam(const std::string &key, std::string &s) const
void sendGoal(const Goal &goal, SimpleDoneCallback done_cb=SimpleDoneCallback(), SimpleActiveCallback active_cb=SimpleActiveCallback(), SimpleFeedbackCallback feedback_cb=SimpleFeedbackCallback())
boost::shared_ptr< const TestTrajectory > TestTrajectoryConstPtr
const std::string & getNamespace() const
static Time now()
ROSCPP_DECL void shutdown()
static const std::size_t TRAJ_POINTS


ros_control_boilerplate
Author(s): Dave Coleman
autogenerated on Mon Feb 28 2022 23:27:26