current_state_monitor_test.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2023, University of Hamburg
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 copyright holder 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: Michael 'v4hn' Goerner
36  Desc: Tests for CurrentStateMonitor
37 */
38 
39 // ROS
40 #include <ros/ros.h>
41 
42 // Testing
43 #include <gtest/gtest.h>
45 
46 // Main class
48 #include <sensor_msgs/JointState.h>
49 
50 #include <future>
51 
52 class CurrentStateMonitorTest : public ::testing::Test
53 {
54 public:
55  void SetUp() override
56  {
58  .addChain("a->b->c", "revolute")
59  .addCollisionBox("a", { 0.1, 0.1, 0.1 },
60  [] {
61  geometry_msgs::Pose p;
62  p.orientation.w = 1.0;
63  return p;
64  }())
65  .addGroupChain("a", "c", "group")
66  .addGroup({ "a" }, { "a-b-joint" }, "group_a")
67  .build();
68 
69  joint_state_pub_ = nh.advertise<sensor_msgs::JointState>("joint_states", 1, true);
70 
71  csm = std::make_unique<planning_scene_monitor::CurrentStateMonitor>(robot_model_ptr, nullptr);
72  csm->startStateMonitor();
73 
74  js_a.name = { "a-b-joint" };
75  js_a.position = { 0.1 };
76  js_a.velocity = { 0.1 };
77  js_a.header.stamp = ros::Time{ 10.0 };
78 
79  js_b.name = { "b-c-joint" };
80  js_b.position = { 0.2 };
81  js_b.velocity = { 0.2 };
82  js_b.header.stamp = ros::Time{ 9.0 };
83 
84  js_ab.name = { "a-b-joint", "b-c-joint" };
85  js_ab.position = { 0.3, 0.3 };
86  js_ab.velocity = { 0.3, 0.3 };
87  js_ab.header.stamp = ros::Time{ 11.0 };
88 
89  js_a_old.name = { "a-b-joint" };
90  js_a_old.position = { 0.4 };
91  js_a_old.velocity = { 0.4 };
92  js_a_old.header.stamp = ros::Time{ 9.0 };
93  }
94 
95  void TearDown() override
96  {
98  }
99 
100  void sendJointStateAndWait(const sensor_msgs::JointState& js)
101  {
102  std::promise<void> promise;
103  auto future = promise.get_future();
104  csm->addUpdateCallback([&promise](const sensor_msgs::JointStateConstPtr& /*unused*/) { promise.set_value(); });
106 
107  std::future_status status{ std::future_status::timeout };
108  EXPECT_NO_THROW(status = future.wait_for(std::chrono::seconds{ 1 }));
109  csm->clearUpdateCallbacks();
110  EXPECT_EQ(std::future_status::ready, status);
111  }
112 
113 protected:
115  moveit::core::RobotModelConstPtr robot_model_ptr;
116  planning_scene_monitor::CurrentStateMonitorPtr csm;
118 
119  sensor_msgs::JointState js_a, js_b, js_ab, js_a_old;
120 };
121 
122 TEST_F(CurrentStateMonitorTest, CompleteStateTest)
123 {
124  EXPECT_FALSE(csm->haveCompleteState());
125 
126  sendJointStateAndWait(js_a);
127 
128  EXPECT_FALSE(csm->haveCompleteState());
129 
130  sendJointStateAndWait(js_ab);
131 
132  EXPECT_TRUE(csm->haveCompleteState());
133 }
134 
136 {
137  sendJointStateAndWait(js_a);
138  EXPECT_EQ(js_a.position[0], csm->getCurrentState()->getVariablePosition("a-b-joint"));
139 
140  sendJointStateAndWait(js_ab);
141  std::vector<double> positions;
142  csm->getCurrentState()->copyJointGroupPositions("group", positions);
143  EXPECT_EQ(positions, js_ab.position);
144 }
145 
146 TEST_F(CurrentStateMonitorTest, IncrementalTimeStamps)
147 {
148  sendJointStateAndWait(js_a);
149  EXPECT_EQ(js_a.header.stamp, csm->getCurrentStateTime());
150 
151  sendJointStateAndWait(js_b);
152  EXPECT_EQ(js_b.header.stamp, csm->getCurrentStateTime())
153  << "older partial joint state was ignored in current state retrieval!";
154 
155  js_b.position = { 0.25 };
156  js_b.header.stamp = ros::Time{ 10.5 };
157  sendJointStateAndWait(js_b);
158  EXPECT_EQ(js_a.header.stamp, csm->getCurrentStateTime())
159  << "older partial joint state was ignored in current state retrieval!";
160 
161  sendJointStateAndWait(js_ab);
162  EXPECT_EQ(js_ab.header.stamp, csm->getCurrentStateTime()) << "newer stamp did not update csm";
163 
164  // send old state for a joint known at a more current time to trigger rosbag loop detection
165  sendJointStateAndWait(js_a_old);
166  EXPECT_FALSE(csm->haveCompleteState())
167  << "jumped back in time for a known joint, but csm still claims it knows all joints";
168  EXPECT_EQ(js_a_old.header.stamp, csm->getCurrentStateTime())
169  << "jumping back for a known joint did not reset state time";
170  EXPECT_EQ(js_a_old.position[0], csm->getCurrentState()->getVariablePosition("a-b-joint"));
171 }
172 
173 TEST_F(CurrentStateMonitorTest, NonMonotonicTimeStampsDueToPartialJoints)
174 {
175  sendJointStateAndWait(js_a);
176  EXPECT_EQ(js_a.header.stamp, csm->getCurrentStateTime());
177 
178  sendJointStateAndWait(js_b);
179  EXPECT_EQ(js_b.header.stamp, csm->getCurrentStateTime())
180  << "older partial joint state was ignored in current state retrieval!";
181  EXPECT_EQ(js_a.header.stamp, csm->getCurrentStateTime("group_a"))
182  << "Group is aware of the timestamp of non-group joints!";
183 
184  js_b.position = { 0.25 };
185  js_b.header.stamp = ros::Time{ 13.0 };
186  sendJointStateAndWait(js_b);
187  EXPECT_EQ(js_a.header.stamp, csm->getCurrentStateTime())
188  << "older partial joint state was ignored in current state retrieval!";
189 }
190 
191 int main(int argc, char** argv)
192 {
193  testing::InitGoogleTest(&argc, argv);
194  ros::init(argc, argv, "current_state_monitor_test");
195 
197  spinner.start();
198 
199  int result = RUN_ALL_TESTS();
200 
201  return result;
202 }
moveit::core::RobotModelBuilder::addGroupChain
RobotModelBuilder & addGroupChain(const std::string &base_link, const std::string &tip_link, const std::string &name="")
ros::Publisher
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
CurrentStateMonitorTest
Definition: current_state_monitor_test.cpp:52
ros.h
CurrentStateMonitorTest::js_ab
sensor_msgs::JointState js_ab
Definition: current_state_monitor_test.cpp:151
ros::AsyncSpinner
main
int main(int argc, char **argv)
Definition: current_state_monitor_test.cpp:191
current_state_monitor.h
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
EXPECT_TRUE
#define EXPECT_TRUE(args)
CurrentStateMonitorTest::js_a_old
sensor_msgs::JointState js_a_old
Definition: current_state_monitor_test.cpp:151
spinner
void spinner()
moveit::core::RobotModelBuilder::addCollisionBox
RobotModelBuilder & addCollisionBox(const std::string &link_name, const std::vector< double > &dims, geometry_msgs::Pose origin)
ros::Publisher::shutdown
void shutdown()
CurrentStateMonitorTest::TearDown
void TearDown() override
Definition: current_state_monitor_test.cpp:127
CurrentStateMonitorTest::sendJointStateAndWait
void sendJointStateAndWait(const sensor_msgs::JointState &js)
Definition: current_state_monitor_test.cpp:132
CurrentStateMonitorTest::csm
planning_scene_monitor::CurrentStateMonitorPtr csm
Definition: current_state_monitor_test.cpp:148
ros::Time
moveit::core::RobotModelBuilder
CurrentStateMonitorTest::SetUp
void SetUp() override
Definition: current_state_monitor_test.cpp:87
moveit::core::RobotModelBuilder::addChain
RobotModelBuilder & addChain(const std::string &section, const std::string &type, const std::vector< geometry_msgs::Pose > &joint_origins={}, urdf::Vector3 joint_axis=urdf::Vector3(1.0, 0.0, 0.0))
TEST_F
TEST_F(CurrentStateMonitorTest, CompleteStateTest)
Definition: current_state_monitor_test.cpp:122
CurrentStateMonitorTest::robot_model_ptr
moveit::core::RobotModelConstPtr robot_model_ptr
Definition: current_state_monitor_test.cpp:147
CurrentStateMonitorTest::nh
ros::NodeHandle nh
Definition: current_state_monitor_test.cpp:146
moveit::core::RobotModelBuilder::addGroup
RobotModelBuilder & addGroup(const std::vector< std::string > &links, const std::vector< std::string > &joints, const std::string &name)
CurrentStateMonitorTest::js_b
sensor_msgs::JointState js_b
Definition: current_state_monitor_test.cpp:151
CurrentStateMonitorTest::joint_state_pub_
ros::Publisher joint_state_pub_
Definition: current_state_monitor_test.cpp:149
robot_model_test_utils.h
EXPECT_EQ
#define EXPECT_EQ(a, b)
EXPECT_FALSE
#define EXPECT_FALSE(args)
ros::NodeHandle
CurrentStateMonitorTest::js_a
sensor_msgs::JointState js_a
Definition: current_state_monitor_test.cpp:151


planning
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Thu Nov 21 2024 03:24:18