joint_trajectory.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019, the ypspur_ros authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <ros/ros.h>
31 
32 #include <rosgraph_msgs/Clock.h>
33 #include <sensor_msgs/JointState.h>
34 #include <trajectory_msgs/JointTrajectory.h>
35 
36 #include <gtest/gtest.h>
37 
38 TEST(JointTrajectory, CommandValidation)
39 {
40  ros::WallDuration wait(0.005);
41  ros::Duration clock_step(0.05);
42 
43  ros::NodeHandle nh;
44  ros::Publisher pub_cmd =
45  nh.advertise<trajectory_msgs::JointTrajectory>("joint_trajectory", 1, true);
46  ros::Publisher pub_clock =
47  nh.advertise<rosgraph_msgs::Clock>("clock", 100);
48 
49  sensor_msgs::JointState::ConstPtr joint_states;
50  const boost::function<void(const sensor_msgs::JointState::ConstPtr&)> cb_joint =
51  [&joint_states](const sensor_msgs::JointState::ConstPtr& msg) -> void
52  {
53  joint_states = msg;
54  };
55  ros::Subscriber sub_joint_states =
56  nh.subscribe("joint_states", 100, cb_joint);
57 
58  rosgraph_msgs::Clock clock;
59  clock.clock.fromNSec(ros::WallTime::now().toNSec());
60  pub_clock.publish(clock);
61 
62  // Wait until ypspur_ros
63  for (int i = 0; i < 200 * 30; ++i)
64  {
65  clock.clock += clock_step;
66  pub_clock.publish(clock);
67  wait.sleep();
68  ros::spinOnce();
69  if (joint_states)
70  break;
71  }
72  ASSERT_TRUE(static_cast<bool>(joint_states));
73 
74  // Publish valid command
75  trajectory_msgs::JointTrajectory cmd;
76  cmd.header.stamp = clock.clock;
77  cmd.joint_names.resize(1);
78  cmd.joint_names[0] = "joint0";
79  cmd.points.resize(1);
80  cmd.points[0].time_from_start = ros::Duration(1);
81  cmd.points[0].positions.resize(1);
82  cmd.points[0].positions[0] = 1.0;
83  cmd.points[0].velocities.resize(1);
84  cmd.points[0].velocities[0] = 1.0;
85  pub_cmd.publish(cmd);
86  wait.sleep();
87 
88  for (int i = 0; i < 50; ++i)
89  {
90  clock.clock += clock_step;
91  pub_clock.publish(clock);
92  wait.sleep();
93  ros::spinOnce();
94  }
95 
96  // Valid command must not be ignored
97  ASSERT_TRUE(static_cast<bool>(joint_states));
98  ASSERT_EQ(joint_states->name.size(), 1u);
99  ASSERT_EQ(joint_states->name[0], "joint0");
100  ASSERT_EQ(joint_states->velocity.size(), 1u);
101  ASSERT_NEAR(joint_states->velocity[0], 1.0, 0.1)
102  << "Valid joint_trajectory must not be ignored";
103 
104  // Stop
105  cmd.header.stamp = clock.clock;
106  cmd.points[0].positions[0] = 0.0;
107  cmd.points[0].velocities[0] = 0.0;
108  pub_cmd.publish(cmd);
109  wait.sleep();
110  for (int i = 0; i < 50; ++i)
111  {
112  clock.clock += clock_step;
113  pub_clock.publish(clock);
114  wait.sleep();
115  ros::spinOnce();
116  }
117  ASSERT_NEAR(joint_states->velocity[0], 0.0, 0.1)
118  << "Valid joint_trajectory must not be ignored";
119 
120  // Publish outdated command
121  cmd.header.stamp = clock.clock - ros::Duration(2.0);
122  cmd.points[0].positions[0] = 1.0;
123  cmd.points[0].velocities[0] = 1.0;
124  pub_cmd.publish(cmd);
125  wait.sleep();
126  for (int i = 0; i < 50; ++i)
127  {
128  clock.clock += clock_step;
129  pub_clock.publish(clock);
130  wait.sleep();
131  ros::spinOnce();
132  }
133  ASSERT_NEAR(joint_states->velocity[0], 0.0, 0.1)
134  << "Outdated joint_trajectory must be ignored";
135 }
136 
137 int main(int argc, char** argv)
138 {
139  testing::InitGoogleTest(&argc, argv);
140  ros::init(argc, argv, "test_joint_trajectory");
141 
142  return RUN_ALL_TESTS();
143 }
TEST(JointTrajectory, CommandValidation)
void publish(const boost::shared_ptr< M > &message) const
int main(int argc, char **argv)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool sleep() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
static WallTime now()
ROSCPP_DECL void spinOnce()


ypspur_ros
Author(s): Atsushi Watanabe
autogenerated on Thu May 13 2021 03:01:26