moveit2
The MoveIt Motion Planning Framework for ROS 2.
servo_ros_fixture.hpp
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 : Resources used by servo ROS integration tests
37  Title : servo_ros_fixture.hpp
38  Project : moveit_servo
39  Created : 07/23/2023
40 */
41 
42 #pragma once
43 
44 #include <gtest/gtest.h>
45 #include <moveit_msgs/msg/servo_status.hpp>
46 #include <moveit_msgs/srv/servo_command_type.hpp>
48 #include <rclcpp/client.hpp>
49 #include <rclcpp/node.hpp>
50 #include <rclcpp/publisher.hpp>
51 #include <rclcpp/qos.hpp>
52 #include <sensor_msgs/msg/joint_state.hpp>
53 #include <trajectory_msgs/msg/joint_trajectory.hpp>
54 
55 class ServoRosFixture : public testing::Test
56 {
57 protected:
58  void statusCallback(const moveit_msgs::msg::ServoStatus::ConstSharedPtr& msg)
59  {
60  status_ = static_cast<moveit_servo::StatusCode>(msg->code);
61  status_count_++;
62  }
63 
64  void jointStateCallback(const sensor_msgs::msg::JointState::ConstSharedPtr& msg)
65  {
66  joint_states_ = *msg;
67  state_count_++;
68  }
69 
70  void trajectoryCallback(const trajectory_msgs::msg::JointTrajectory::ConstSharedPtr& msg)
71  {
72  published_trajectory_ = *msg;
73  traj_count_++;
74  }
75 
76  void SetUp() override
77  {
78  // Create a node to be given to Servo.
79  servo_test_node_ = std::make_shared<rclcpp::Node>("moveit_servo_test");
80 
82 
83  status_subscriber_ = servo_test_node_->create_subscription<moveit_msgs::msg::ServoStatus>(
84  "/servo_node/status", rclcpp::SystemDefaultsQoS(),
85  [this](const moveit_msgs::msg::ServoStatus::ConstSharedPtr& msg) { return statusCallback(msg); });
86 
87  joint_state_subscriber_ = servo_test_node_->create_subscription<sensor_msgs::msg::JointState>(
88  "/joint_states", rclcpp::SystemDefaultsQoS(),
89  [this](const sensor_msgs::msg::JointState::ConstSharedPtr& msg) { return jointStateCallback(msg); });
90 
91  trajectory_subscriber_ = servo_test_node_->create_subscription<trajectory_msgs::msg::JointTrajectory>(
92  "/panda_arm_controller/joint_trajectory", rclcpp::SystemDefaultsQoS(),
93  [this](const trajectory_msgs::msg::JointTrajectory::ConstSharedPtr& msg) { return trajectoryCallback(msg); });
94 
96  servo_test_node_->create_client<moveit_msgs::srv::ServoCommandType>("/servo_node/switch_command_type");
97 
99 
100  executor_.add_node(servo_test_node_);
101  executor_thread_ = std::thread([this]() { executor_.spin(); });
102  }
103 
104  void TearDown() override
105  {
106  executor_.remove_node(servo_test_node_);
107  executor_.cancel();
108  if (executor_thread_.joinable())
109  {
110  executor_thread_.join();
111  }
112  }
113 
115  {
116  auto logger = servo_test_node_->get_logger();
117  while (!switch_input_client_->service_is_ready())
118  {
119  if (!rclcpp::ok())
120  {
121  RCLCPP_ERROR(logger, "Interrupted while waiting for the service. Exiting.");
122  std::exit(EXIT_FAILURE);
123  }
124 
125  rclcpp::sleep_for(std::chrono::milliseconds(500));
126  }
127  RCLCPP_INFO(logger, "MoveIt Servo input switching service ready!");
128  }
129 
131  {
132  auto logger = servo_test_node_->get_logger();
133  auto wait_timeout = rclcpp::Duration::from_seconds(5);
134  auto start_time = servo_test_node_->now();
135 
136  while (rclcpp::ok() && state_count_ == 0)
137  {
138  rclcpp::sleep_for(std::chrono::milliseconds(500));
139  auto elapsed_time = servo_test_node_->now() - start_time;
140  if (elapsed_time >= wait_timeout)
141  {
142  RCLCPP_ERROR(logger, "Timed out waiting for joint states");
143  FAIL();
144  }
145  }
146  }
147 
149  {
150  }
151 
152  std::shared_ptr<rclcpp::Node> servo_test_node_;
153 
154  // Executor and a thread to run the executor.
155  rclcpp::executors::SingleThreadedExecutor executor_;
156  std::thread executor_thread_;
157 
158  rclcpp::Subscription<moveit_msgs::msg::ServoStatus>::SharedPtr status_subscriber_;
159  rclcpp::Subscription<sensor_msgs::msg::JointState>::SharedPtr joint_state_subscriber_;
160  rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr trajectory_subscriber_;
161  rclcpp::Client<moveit_msgs::srv::ServoCommandType>::SharedPtr switch_input_client_;
162 
163  sensor_msgs::msg::JointState joint_states_;
164  trajectory_msgs::msg::JointTrajectory published_trajectory_;
165 
166  std::atomic<int> status_count_;
167  std::atomic<moveit_servo::StatusCode> status_;
168 
169  std::atomic<int> state_count_;
170  std::atomic<int> traj_count_;
171 };
trajectory_msgs::msg::JointTrajectory published_trajectory_
std::atomic< int > traj_count_
std::atomic< moveit_servo::StatusCode > status_
rclcpp::executors::SingleThreadedExecutor executor_
sensor_msgs::msg::JointState joint_states_
std::thread executor_thread_
void SetUp() override
std::atomic< int > status_count_
std::atomic< int > state_count_
rclcpp::Subscription< sensor_msgs::msg::JointState >::SharedPtr joint_state_subscriber_
void jointStateCallback(const sensor_msgs::msg::JointState::ConstSharedPtr &msg)
std::shared_ptr< rclcpp::Node > servo_test_node_
rclcpp::Subscription< moveit_msgs::msg::ServoStatus >::SharedPtr status_subscriber_
rclcpp::Client< moveit_msgs::srv::ServoCommandType >::SharedPtr switch_input_client_
void trajectoryCallback(const trajectory_msgs::msg::JointTrajectory::ConstSharedPtr &msg)
void TearDown() override
void statusCallback(const moveit_msgs::msg::ServoStatus::ConstSharedPtr &msg)
rclcpp::Subscription< trajectory_msgs::msg::JointTrajectory >::SharedPtr trajectory_subscriber_