joint_trajectory.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2019, the ypspur_ros authors
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the copyright holder nor the names of its 
00014  *       contributors may be used to endorse or promote products derived from 
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include <ros/ros.h>
00031 
00032 #include <rosgraph_msgs/Clock.h>
00033 #include <sensor_msgs/JointState.h>
00034 #include <trajectory_msgs/JointTrajectory.h>
00035 
00036 #include <gtest/gtest.h>
00037 
00038 TEST(JointTrajectory, CommandValidation)
00039 {
00040   ros::WallDuration wait(0.005);
00041   ros::Duration clock_step(0.05);
00042 
00043   ros::NodeHandle nh;
00044   ros::Publisher pub_cmd =
00045       nh.advertise<trajectory_msgs::JointTrajectory>("joint_trajectory", 1, true);
00046   ros::Publisher pub_clock =
00047       nh.advertise<rosgraph_msgs::Clock>("clock", 100);
00048 
00049   sensor_msgs::JointState::ConstPtr joint_states;
00050   const boost::function<void(const sensor_msgs::JointState::ConstPtr &)> cb_joint =
00051       [&joint_states](const sensor_msgs::JointState::ConstPtr &msg) -> void
00052   {
00053     joint_states = msg;
00054   };
00055   ros::Subscriber sub_joint_states =
00056       nh.subscribe("joint_states", 100, cb_joint);
00057 
00058   rosgraph_msgs::Clock clock;
00059   clock.clock.fromNSec(ros::WallTime::now().toNSec());
00060   pub_clock.publish(clock);
00061 
00062   // Wait until ypspur_ros
00063   for (int i = 0; i < 1000; ++i)
00064   {
00065     wait.sleep();
00066     ros::spinOnce();
00067     if (joint_states)
00068       break;
00069   }
00070 
00071   // Publish valid command
00072   trajectory_msgs::JointTrajectory cmd;
00073   cmd.header.stamp = clock.clock;
00074   cmd.joint_names.resize(1);
00075   cmd.joint_names[0] = "joint0";
00076   cmd.points.resize(1);
00077   cmd.points[0].time_from_start = ros::Duration(1);
00078   cmd.points[0].positions.resize(1);
00079   cmd.points[0].positions[0] = 1.0;
00080   cmd.points[0].velocities.resize(1);
00081   cmd.points[0].velocities[0] = 1.0;
00082   pub_cmd.publish(cmd);
00083   wait.sleep();
00084 
00085   for (int i = 0; i < 50; ++i)
00086   {
00087     clock.clock += clock_step;
00088     pub_clock.publish(clock);
00089     wait.sleep();
00090     ros::spinOnce();
00091   }
00092 
00093   // Valid command must not be ignored
00094   ASSERT_TRUE(static_cast<bool>(joint_states));
00095   ASSERT_EQ(joint_states->name.size(), 1);
00096   ASSERT_EQ(joint_states->name[0], "joint0");
00097   ASSERT_EQ(joint_states->velocity.size(), 1);
00098   ASSERT_NEAR(joint_states->velocity[0], 1.0, 0.1)
00099       << "Valid joint_trajectory must not be ignored";
00100 
00101   // Stop
00102   cmd.header.stamp = clock.clock;
00103   cmd.points[0].positions[0] = 0.0;
00104   cmd.points[0].velocities[0] = 0.0;
00105   pub_cmd.publish(cmd);
00106   wait.sleep();
00107   for (int i = 0; i < 50; ++i)
00108   {
00109     clock.clock += clock_step;
00110     pub_clock.publish(clock);
00111     wait.sleep();
00112     ros::spinOnce();
00113   }
00114   ASSERT_NEAR(joint_states->velocity[0], 0.0, 0.1)
00115       << "Valid joint_trajectory must not be ignored";
00116 
00117   // Publish outdated command
00118   cmd.header.stamp = clock.clock - ros::Duration(2.0);
00119   cmd.points[0].positions[0] = 1.0;
00120   cmd.points[0].velocities[0] = 1.0;
00121   pub_cmd.publish(cmd);
00122   wait.sleep();
00123   for (int i = 0; i < 50; ++i)
00124   {
00125     clock.clock += clock_step;
00126     pub_clock.publish(clock);
00127     wait.sleep();
00128     ros::spinOnce();
00129   }
00130   ASSERT_NEAR(joint_states->velocity[0], 0.0, 0.1)
00131       << "Outdated joint_trajectory must be ignored";
00132 }
00133 
00134 int main(int argc, char **argv)
00135 {
00136   testing::InitGoogleTest(&argc, argv);
00137   ros::init(argc, argv, "test_joint_trajectory");
00138 
00139   return RUN_ALL_TESTS();
00140 }


ypspur_ros
Author(s): Atsushi Watanabe
autogenerated on Thu Jun 6 2019 20:19:02