moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
servo.hpp
Go to the documentation of this file.
1/*******************************************************************************
2 * BSD 3-Clause License
3 *
4 * Copyright (c) 2019, Los Alamos National Security, LLC
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 are met:
9 *
10 * * Redistributions of source code must retain the above copyright notice, this
11 * list of conditions and the following disclaimer.
12 *
13 * * Redistributions in binary form must reproduce the above copyright notice,
14 * this list of conditions and the following disclaimer in the documentation
15 * and/or other materials provided with the distribution.
16 *
17 * * Neither the name of the copyright holder nor the names of its
18 * contributors may be used to endorse or promote products derived from
19 * this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
24 * ARE
25 * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
26 * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
27 * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
28 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
30 * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
31 * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
32 *******************************************************************************/
33
34/* Title : servo.hpp
35 * Project : moveit_servo
36 * Created : 05/17/2023
37 * Author : Brian O'Neil, Andy Zelenak, Blake Anderson, V Mohammed Ibrahim
38 *
39 * Description : The core servoing logic.
40 */
41
42#pragma once
43
44#include <moveit_servo_lib_parameters.hpp>
51#include <pluginlib/class_loader.hpp>
52#include <sensor_msgs/msg/joint_state.hpp>
53#include <tf2_eigen/tf2_eigen.hpp>
54#include <tf2_ros/transform_listener.h>
55#include <variant>
56#include <rclcpp/logger.hpp>
57#include <queue>
58
59namespace moveit_servo
60{
61
62class Servo
63{
64public:
65 Servo(const rclcpp::Node::SharedPtr& node, std::shared_ptr<const servo::ParamListener> servo_param_listener,
66 const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor);
67
68 ~Servo();
69
70 // Disable copy construction.
71 Servo(const Servo&) = delete;
72
73 // Disable copy assignment.
74 Servo& operator=(Servo&) = delete;
75
82 KinematicState getNextJointState(const moveit::core::RobotStatePtr& robot_state, const ServoInput& command);
83
88 void setCommandType(const CommandType& command_type);
89
95
100 StatusCode getStatus() const;
101
106 std::string getStatusMessage() const;
107
112 void setCollisionChecking(const bool check_collision);
113
117 servo::Params& getParams();
118
125 KinematicState getCurrentRobotState(bool block_for_current_state) const;
126
132 std::pair<bool, KinematicState> smoothHalt(const KinematicState& halt_state);
133
138 void doSmoothing(KinematicState& state);
139
144 void resetSmoothing(const KinematicState& state);
145
146private:
156 std::optional<Eigen::Isometry3d> getPlanningToCommandFrameTransform(const std::string& command_frame,
157 const std::string& planning_frame) const;
158
169 std::optional<TwistCommand> toPlanningFrame(const TwistCommand& command, const std::string& planning_frame) const;
170
177 std::optional<PoseCommand> toPlanningFrame(const PoseCommand& command, const std::string& planning_frame) const;
178
185 Eigen::VectorXd jointDeltaFromCommand(const ServoInput& command, const moveit::core::RobotStatePtr& robot_state);
186
192 bool validateParams(const servo::Params& servo_params);
193
197 bool updateParams();
198
202 void setSmoothingPlugin();
203
211 KinematicState haltJoints(const std::vector<size_t>& joints_to_halt, const KinematicState& current_state,
212 const KinematicState& target_state) const;
213
214 // Variables
215
216 StatusCode servo_status_;
217 // This needs to be threadsafe so it can be updated in realtime.
218 std::atomic<CommandType> expected_command_type_;
219
220 servo::Params servo_params_;
221 const rclcpp::Node::SharedPtr node_;
222 rclcpp::Logger logger_;
223 std::shared_ptr<const servo::ParamListener> servo_param_listener_;
224 planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_;
225
226 // This value will be updated by CollisionMonitor in a separate thread.
227 std::atomic<double> collision_velocity_scale_ = 1.0;
228 std::unique_ptr<CollisionMonitor> collision_monitor_;
229
230 // Pointer to the (optional) smoothing plugin.
231 pluginlib::UniquePtr<online_signal_smoothing::SmoothingBaseClass> smoother_ = nullptr;
232
233 // Map between joint subgroup names and corresponding joint name - move group indices map
234 std::unordered_map<std::string, JointNameToMoveGroupIndexMap> joint_name_to_index_maps_;
235
236 // The current joint limit safety margins for each active joint position variable.
237 std::vector<double> joint_limit_margins_;
238};
239
240} // namespace moveit_servo
void setCommandType(const CommandType &command_type)
Set the type of incoming servo command.
Definition servo.cpp:332
CommandType getCommandType() const
Get the type of command that servo is currently expecting.
Definition servo.cpp:327
KinematicState getCurrentRobotState(bool block_for_current_state) const
Get the current state of the robot as given by planning scene monitor. This may block if a current ro...
Definition servo.cpp:644
Servo(const Servo &)=delete
std::string getStatusMessage() const
Get the message associated with the current servo status.
Definition servo.cpp:322
std::pair< bool, KinematicState > smoothHalt(const KinematicState &halt_state)
Smoothly halt at a commanded state when command goes stale.
Definition servo.cpp:663
StatusCode getStatus() const
Get the current status of servo.
Definition servo.cpp:317
Servo & operator=(Servo &)=delete
servo::Params & getParams()
Returns the most recent servo parameters.
Definition servo.cpp:312
void resetSmoothing(const KinematicState &state)
Resets the smoothing plugin, if set, to a specified state.
Definition servo.cpp:172
void setCollisionChecking(const bool check_collision)
Start/Stop collision checking thread.
Definition servo.cpp:180
KinematicState getNextJointState(const moveit::core::RobotStatePtr &robot_state, const ServoInput &command)
Computes the joint state required to follow the given command.
Definition servo.cpp:470
void doSmoothing(KinematicState &state)
Applies smoothing to an input state, if a smoothing plugin is set.
Definition servo.cpp:164
std::variant< JointJogCommand, TwistCommand, PoseCommand > ServoInput