41 #include <control_msgs/FollowJointTrajectoryAction.h> 42 #include <trajectory_msgs/JointTrajectory.h> 63 "No joint trajectory controller parameter found on the parameter server");
73 ROS_INFO_NAMED(
"test_trajetory",
"Waiting for action server to start.");
77 ROS_INFO_NAMED(
"test_trajetory",
"Action server started, sending goal.");
80 control_msgs::FollowJointTrajectoryGoal goal;
82 std::cout <<
"Trajectry:\n" << goal.trajectory << std::endl;
86 double wait_extra_padding = 2;
88 ros::Duration(goal.trajectory.points.back().time_from_start.toSec() + wait_extra_padding));
90 if (finished_before_timeout)
96 ROS_INFO_NAMED(
"test_trajetory",
"Action did not finish before the time out.");
106 std::vector<std::string> joint_names;
107 double min_joint_value = -3.14;
108 double max_joint_value = 3.14;
112 if (joint_names.size() == 0)
115 "Not joints found on parameter server for controller, did you load the proper yaml file?" 122 ROS_DEBUG_STREAM_NAMED(
"test_trajectory",
"Creating trajectory with joint values from " << min_joint_value <<
" to " 126 trajectory_msgs::JointTrajectory trajectory;
128 trajectory.joint_names = joint_names;
131 trajectory.points.resize(TRAJ_POINTS);
134 trajectory.points[i].positions.resize(joint_names.size());
136 for (std::size_t j = 0; j < joint_names.size(); ++j)
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);
147 double dRand(
double dMin,
double dMax)
149 double d = (double)rand() / RAND_MAX;
150 return dMin + d * (dMax - dMin);
167 int main(
int argc,
char** argv)
169 ros::init(argc, argv,
"test_trajectory");
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)
bool waitForServer(const ros::Duration &timeout=ros::Duration(0, 0)) const
TestTrajectory()
Constructor.
SimpleClientGoalState getState() const
std::string trajectory_controller
#define ROS_FATAL_STREAM_NAMED(name, args)
bool getParam(const std::string &key, std::string &s) const
ros::NodeHandle nh_private_
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
ROSCPP_DECL void shutdown()
static const std::size_t TRAJ_POINTS