moveit2
The MoveIt Motion Planning Framework for ROS 2.
servo_parameters.h
Go to the documentation of this file.
1 /*******************************************************************************
2  * Title : servo_parameters.h
3  * Project : moveit_servo
4  * Created : 1/11/2019
5  * Author : Brian O'Neil, Andy Zelenak, Blake Anderson
6  *
7  * BSD 3-Clause License
8  *
9  * Copyright (c) 2019, Los Alamos National Security, LLC
10  * All rights reserved.
11  *
12  * Redistribution and use in source and binary forms, with or without
13  * modification, are permitted provided that the following conditions are met:
14  *
15  * * Redistributions of source code must retain the above copyright notice, this
16  * list of conditions and the following disclaimer.
17  *
18  * * Redistributions in binary form must reproduce the above copyright notice,
19  * this list of conditions and the following disclaimer in the documentation
20  * and/or other materials provided with the distribution.
21  *
22  * * Neither the name of the copyright holder nor the names of its
23  * contributors may be used to endorse or promote products derived from
24  * this software without specific prior written permission.
25  *
26  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
27  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
28  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
29  * ARE
30  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
31  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
32  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
33  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
34  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
35  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
36  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
37  *******************************************************************************/
38 
39 #pragma once
40 
41 #include <rclcpp/node.hpp>
42 #include <mutex>
43 #include <thread>
44 #include <vector>
45 
47 namespace moveit_servo
48 {
49 using SetParameterCallbackType = std::function<rcl_interfaces::msg::SetParametersResult(const rclcpp::Parameter&)>;
50 
51 // ROS params to be read. See the yaml file in /config for a description of each.
53 {
54  using SharedConstPtr = std::shared_ptr<const ServoParameters>;
55 
56  // Parameter namespace
57  const std::string ns;
58 
59  // ROS Parameters
60  // Note that all of these are effectively const because the only way to create one of these
61  // is as a shared_ptr to a constant struct.
62  bool use_gazebo{ false };
63  std::string status_topic{ "~/status" };
64  // Properties of incoming commands
65  std::string cartesian_command_in_topic{ "~/delta_twist_cmds" };
66  std::string joint_command_in_topic{ "~/delta_joint_cmds" };
67  std::string robot_link_command_frame{ "panda_link0" };
68  std::string command_in_type{ "unitless" };
69  double linear_scale{ 0.4 };
70  double rotational_scale{ 0.8 };
71  double joint_scale{ 0.5 };
72  // Properties of Servo calculations
74  // Properties of outgoing commands
75  std::string command_out_topic{ "/panda_arm_controller/joint_trajectory" };
76  double publish_period{ 0.034 };
77  std::string command_out_type{ "trajectory_msgs/JointTrajectory" };
81  // Plugins for smoothing outgoing commands
82  std::string joint_topic{ "/joint_states" };
83  std::string smoothing_filter_plugin_name{ "online_signal_smoothing::ButterworthFilterPlugin" };
84  // MoveIt properties
85  std::string move_group_name{ "panda_arm" };
86  std::string planning_frame{ "panda_link0" };
87  std::string ee_frame_name{ "panda_link8" };
91  };
92  // Stopping behaviour
93  double incoming_command_timeout{ 0.1 };
97  // Configure handling of singularities and joint limits
101  double joint_limit_margin{ 0.1 };
102  bool low_latency_mode{ false };
103  // Collision checking
104  bool check_collisions{ true };
105  double collision_check_rate{ 10.0 };
108 
121  static SharedConstPtr makeServoParameters(const rclcpp::Node::SharedPtr& node, const std::string& ns = "moveit_servo",
122  bool dynamic_parameters = true);
123 
131  [[nodiscard]] bool registerSetParameterCallback(const std::string& name,
132  const SetParameterCallbackType& callback) const
133  {
134  if (callback_handler_)
135  {
136  const std::lock_guard<std::mutex> guard{ callback_handler_->mutex_ };
137  callback_handler_->set_parameter_callbacks_[name].push_back(callback);
138  return true;
139  }
140  return false;
141  }
142  static ServoParameters get(const std::string& ns,
143  const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr& node_parameters);
144  static std::optional<ServoParameters> validate(ServoParameters parameters);
145 
146 private:
147  // Private constructor because we only want this object to be created through the builder method makeServoParameters
149  {
150  }
151 
152  struct CallbackHandler
153  {
154  // callback handler for the on set parameters callback
155  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_handler_;
156 
157  // mutable so the callback can be registered objects that have const versions of this struct
158  mutable std::mutex mutex_;
159  mutable std::map<std::string, std::vector<SetParameterCallbackType>> set_parameter_callbacks_;
160 
161  // For registering with add_on_set_parameters_callback after initializing data
162  rcl_interfaces::msg::SetParametersResult setParametersCallback(const std::vector<rclcpp::Parameter>& parameters);
163  };
164 
165  std::shared_ptr<CallbackHandler> callback_handler_;
166 
167  static void declare(const std::string& ns,
168  const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr& node_parameters);
169 };
170 
171 } // namespace moveit_servo
static const std::string DEFAULT_PLANNING_SCENE_TOPIC
The name of the topic used by default for receiving full planning scenes or planning scene diffs.
std::function< rcl_interfaces::msg::SetParametersResult(const rclcpp::Parameter &)> SetParameterCallbackType
name
Definition: setup.py:7
std::mutex mutex_
std::shared_ptr< const ServoParameters > SharedConstPtr
static ServoParameters get(const std::string &ns, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &node_parameters)
static SharedConstPtr makeServoParameters(const rclcpp::Node::SharedPtr &node, const std::string &ns="moveit_servo", bool dynamic_parameters=true)
bool registerSetParameterCallback(const std::string &name, const SetParameterCallbackType &callback) const
static std::optional< ServoParameters > validate(ServoParameters parameters)