moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_servo_collision.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2020, PickNik Inc.
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 PickNik Inc. 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 /* Title : test_servo_collision.cpp
36  * Project : moveit_servo
37  * Created : 08/03/2020
38  * Author : Adam Pettinger
39  */
40 
42 #include <moveit_msgs/msg/planning_scene.hpp>
43 
44 namespace moveit_servo
45 {
46 TEST_F(ServoFixture, SelfCollision)
47 {
48  auto log_time_start = node_->now();
49  ASSERT_TRUE(setupStartClient());
50  auto log_time_end = node_->now();
51  RCLCPP_INFO_STREAM(LOGGER, "Setup time: " << (log_time_end - log_time_start).seconds());
52 
53  // Start Servo
54  ASSERT_TRUE(start());
55  EXPECT_EQ(latest_status_, moveit_servo::StatusCode::NO_WARNING);
56 
57  // Look for DECELERATE_FOR_COLLISION status
59 
60  // Publish some joint jog commands that will bring us to collision
61  rclcpp::WallRate publish_loop_rate(test_parameters_->publish_hz);
62  log_time_start = node_->now();
63  size_t iterations = 0;
64  while (!sawTrackedStatus() && iterations++ < test_parameters_->timeout_iterations)
65  {
66  auto msg = std::make_unique<control_msgs::msg::JointJog>();
67  msg->header.stamp = node_->now();
68  msg->header.frame_id = "panda_link3";
69  msg->joint_names.push_back("panda_joint4");
70  msg->velocities.push_back(-1.0);
71  pub_joint_cmd_->publish(std::move(msg));
72  publish_loop_rate.sleep();
73  }
74 
75  EXPECT_LT(iterations, test_parameters_->timeout_iterations);
76  log_time_end = node_->now();
77  RCLCPP_INFO_STREAM(LOGGER, "Wait for collision: " << (log_time_end - log_time_start).seconds());
78 }
79 
80 TEST_F(ServoFixture, ExternalCollision)
81 {
82  // NOTE: This test is meant to be run after the SelfCollision test
83  // It assumes the position is where the robot ends in SelfCollision test
84 
85  auto log_time_start = node_->now();
86  ASSERT_TRUE(setupStartClient());
87  auto log_time_end = node_->now();
88  RCLCPP_INFO_STREAM(LOGGER, "Setup time: " << (log_time_end - log_time_start).seconds());
89 
90  // Start Servo
91  ASSERT_TRUE(start());
92 
93  // Create collision object, in the way of servoing
94  moveit_msgs::msg::CollisionObject collision_object;
95  collision_object.header.frame_id = "panda_link0";
96  collision_object.id = "box";
97 
98  shape_msgs::msg::SolidPrimitive box;
99  box.type = box.BOX;
100  box.dimensions = { 0.1, 0.4, 0.1 };
101 
102  geometry_msgs::msg::Pose box_pose;
103  box_pose.position.x = 0.4;
104  box_pose.position.y = 0.0;
105  box_pose.position.z = 0.4;
106 
107  collision_object.primitives.push_back(box);
108  collision_object.primitive_poses.push_back(box_pose);
109  collision_object.operation = collision_object.ADD;
110 
111  moveit_msgs::msg::PlanningSceneWorld psw;
112  psw.collision_objects.push_back(collision_object);
113 
114  moveit_msgs::msg::PlanningScene ps;
115  ps.is_diff = true;
116  ps.world = psw;
117 
118  // Publish the collision object to the planning scene
119  auto scene_pub = node_->create_publisher<moveit_msgs::msg::PlanningScene>("/planning_scene", 10);
120  scene_pub->publish(ps);
121 
122  // Look for DECELERATE_FOR_COLLISION status
124 
125  // Now publish twist commands that collide with the box
126  rclcpp::WallRate publish_loop_rate(test_parameters_->publish_hz);
127  log_time_start = node_->now();
128  size_t iterations = 0;
129  while (!sawTrackedStatus() && iterations++ < test_parameters_->timeout_iterations)
130  {
131  auto msg = std::make_unique<geometry_msgs::msg::TwistStamped>();
132  msg->header.stamp = node_->now();
133  msg->twist.linear.x = 0.2;
134  pub_twist_cmd_->publish(std::move(msg));
135  publish_loop_rate.sleep();
136  }
137 
138  EXPECT_LT(iterations, test_parameters_->timeout_iterations);
139  log_time_end = node_->now();
140  RCLCPP_INFO_STREAM(LOGGER, "Wait for collision: " << (log_time_end - log_time_start).seconds());
141 }
142 
143 } // namespace moveit_servo
144 
145 int main(int argc, char** argv)
146 {
147  // It is important we init ros before google test because we are going to
148  // create a node during the google test init.
149  rclcpp::init(argc, argv);
150  ::testing::InitGoogleTest(&argc, argv);
151 
152  int ret = RUN_ALL_TESTS();
153  rclcpp::shutdown();
154  return ret;
155 }
TEST_F(PoseTrackingFixture, OutgoingMsgTest)
int main(int argc, char **argv)