moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
test_ros_integration.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2023, 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/* Author : V Mohammed Ibrahim
36 Desc : ROS API integration tests
37 Title : test_ros_integration.cpp
38 Project : moveit_servo
39 Created : 07/23/2023
40*/
41
42#include "servo_ros_fixture.hpp"
43#include <control_msgs/msg/joint_jog.hpp>
44#include <geometry_msgs/msg/pose_stamped.hpp>
45#include <geometry_msgs/msg/twist_stamped.hpp>
46
61namespace
62{
63const int NUM_COMMANDS = 10;
64}
65
66namespace
67{
68TEST_F(ServoRosFixture, testJointJog)
69{
70 waitForJointStates();
71
72 auto joint_jog_publisher = servo_test_node_->create_publisher<control_msgs::msg::JointJog>(
73 "/servo_node/delta_joint_cmds", rclcpp::SystemDefaultsQoS());
74
75 // Call input type service
76 auto request = std::make_shared<moveit_msgs::srv::ServoCommandType::Request>();
77 request->command_type = moveit_msgs::srv::ServoCommandType::Request::JOINT_JOG;
78 auto response = switch_input_client_->async_send_request(request);
79 ASSERT_EQ(response.get()->success, true);
80
81 ASSERT_NE(state_count_, 0);
82
83 control_msgs::msg::JointJog jog_cmd;
84
85 jog_cmd.header.frame_id = "panda_link0";
86 jog_cmd.joint_names.resize(7);
87 jog_cmd.velocities.resize(7);
88 jog_cmd.joint_names = { "panda_joint1", "panda_joint2", "panda_joint3", "panda_joint4",
89 "panda_joint5", "panda_joint6", "panda_joint7" };
90
91 std::fill(jog_cmd.velocities.begin(), jog_cmd.velocities.end(), 0.0);
92
93 jog_cmd.velocities[6] = 0.5;
94
95 size_t count = 0;
96 while (rclcpp::ok() && count < NUM_COMMANDS)
97 {
98 jog_cmd.header.stamp = servo_test_node_->now();
99 joint_jog_publisher->publish(jog_cmd);
100 count++;
101 rclcpp::sleep_for(std::chrono::milliseconds(100));
102 }
103
104 ASSERT_GE(traj_count_, NUM_COMMANDS);
105
106 moveit_servo::StatusCode status = status_;
107 RCLCPP_INFO_STREAM(servo_test_node_->get_logger(), "Status after jointjog: " << static_cast<size_t>(status));
108 ASSERT_EQ(status_, moveit_servo::StatusCode::NO_WARNING);
109}
110
111TEST_F(ServoRosFixture, testTwist)
112{
113 waitForJointStates();
114
115 auto twist_publisher = servo_test_node_->create_publisher<geometry_msgs::msg::TwistStamped>(
116 "/servo_node/delta_twist_cmds", rclcpp::SystemDefaultsQoS());
117
118 auto request = std::make_shared<moveit_msgs::srv::ServoCommandType::Request>();
119 request->command_type = moveit_msgs::srv::ServoCommandType::Request::TWIST;
120 auto response = switch_input_client_->async_send_request(request);
121 ASSERT_EQ(response.get()->success, true);
122
123 ASSERT_NE(state_count_, 0);
124
125 geometry_msgs::msg::TwistStamped twist_cmd;
126 twist_cmd.header.frame_id = "panda_link0"; // Planning frame
127 twist_cmd.twist.linear.x = 0.0;
128 twist_cmd.twist.linear.y = 0.0;
129 twist_cmd.twist.linear.z = 0.0;
130 twist_cmd.twist.angular.x = 0.0;
131 twist_cmd.twist.angular.y = 0.0;
132 twist_cmd.twist.angular.z = 0.5;
133
134 size_t count = 0;
135 while (rclcpp::ok() && count < NUM_COMMANDS)
136 {
137 twist_cmd.header.stamp = servo_test_node_->now();
138 twist_publisher->publish(twist_cmd);
139 count++;
140 rclcpp::sleep_for(std::chrono::milliseconds(100));
141 }
142
143 ASSERT_GE(traj_count_, NUM_COMMANDS);
144
145 moveit_servo::StatusCode status = status_;
146 RCLCPP_INFO_STREAM(servo_test_node_->get_logger(), "Status after twist: " << static_cast<size_t>(status));
147 ASSERT_EQ(status_, moveit_servo::StatusCode::NO_WARNING);
148}
149
150TEST_F(ServoRosFixture, testPose)
151{
152 waitForJointStates();
153
154 auto pose_publisher = servo_test_node_->create_publisher<geometry_msgs::msg::PoseStamped>(
155 "/servo_node/pose_target_cmds", rclcpp::SystemDefaultsQoS());
156
157 auto request = std::make_shared<moveit_msgs::srv::ServoCommandType::Request>();
158 request->command_type = moveit_msgs::srv::ServoCommandType::Request::POSE;
159 auto response = switch_input_client_->async_send_request(request);
160 ASSERT_EQ(response.get()->success, true);
161
162 geometry_msgs::msg::PoseStamped pose_cmd;
163 pose_cmd.header.frame_id = "panda_link0"; // Planning frame
164
165 pose_cmd.pose.position.x = 0.2;
166 pose_cmd.pose.position.y = -0.2;
167 pose_cmd.pose.position.z = 0.6;
168 pose_cmd.pose.orientation.x = 0.7071;
169 pose_cmd.pose.orientation.y = -0.7071;
170 pose_cmd.pose.orientation.z = 0.0;
171 pose_cmd.pose.orientation.w = 0.0;
172
173 ASSERT_NE(state_count_, 0);
174
175 size_t count = 0;
176 while (rclcpp::ok() && count < NUM_COMMANDS)
177 {
178 pose_cmd.header.stamp = servo_test_node_->now();
179 pose_publisher->publish(pose_cmd);
180 count++;
181 rclcpp::sleep_for(std::chrono::milliseconds(100));
182 }
183
184 ASSERT_GE(traj_count_, NUM_COMMANDS);
185
186 moveit_servo::StatusCode status = status_;
187 RCLCPP_INFO_STREAM(servo_test_node_->get_logger(), "Status after pose: " << static_cast<size_t>(status));
188 ASSERT_EQ(status_, moveit_servo::StatusCode::NO_WARNING);
189}
190
191} // namespace
192
193int main(int argc, char** argv)
194{
195 rclcpp::init(argc, argv);
196 ::testing::InitGoogleTest(&argc, argv);
197 int result = RUN_ALL_TESTS();
198 rclcpp::shutdown();
199 return result;
200}
TEST_F(BulletCollisionDetectionTester, DISABLED_ContinuousCollisionSelf)
Continuous self collision checks are not supported yet by the bullet integration.
int main(int argc, char **argv)