41 #include <rclcpp/node.hpp>
122 bool dynamic_parameters =
true);
134 if (callback_handler_)
136 const std::lock_guard<std::mutex> guard{ callback_handler_->mutex_ };
137 callback_handler_->set_parameter_callbacks_[
name].push_back(callback);
143 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr& node_parameters);
152 struct CallbackHandler
155 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr on_set_parameters_callback_handler_;
158 mutable std::mutex
mutex_;
159 mutable std::map<std::string, std::vector<SetParameterCallbackType>> set_parameter_callbacks_;
162 rcl_interfaces::msg::SetParametersResult setParametersCallback(
const std::vector<rclcpp::Parameter>& parameters);
165 std::shared_ptr<CallbackHandler> callback_handler_;
167 static void declare(
const std::string&
ns,
168 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr& node_parameters);
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
std::string monitored_planning_scene_topic
double hard_stop_singularity_threshold
double joint_limit_margin
int num_outgoing_halt_msgs_to_publish
std::shared_ptr< const ServoParameters > SharedConstPtr
std::string cartesian_command_in_topic
double override_velocity_scaling_factor
std::string smoothing_filter_plugin_name
double self_collision_proximity_threshold
bool publish_joint_velocities
double incoming_command_timeout
double scene_collision_proximity_threshold
double leaving_singularity_threshold_multiplier
bool halt_all_joints_in_cartesian_mode
bool is_primary_planning_scene_monitor
std::string command_out_topic
std::string move_group_name
double lower_singularity_threshold
static ServoParameters get(const std::string &ns, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &node_parameters)
std::string ee_frame_name
std::string joint_command_in_topic
bool publish_joint_positions
static SharedConstPtr makeServoParameters(const rclcpp::Node::SharedPtr &node, const std::string &ns="moveit_servo", bool dynamic_parameters=true)
std::string command_out_type
bool publish_joint_accelerations
std::string command_in_type
std::string robot_link_command_frame
bool registerSetParameterCallback(const std::string &name, const SetParameterCallbackType &callback) const
std::string planning_frame
bool halt_all_joints_in_joint_mode
static std::optional< ServoParameters > validate(ServoParameters parameters)
double collision_check_rate