moveit2
The MoveIt Motion Planning Framework for ROS 2.
Classes | Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
moveit_servo::ServoParameters Struct Reference

#include <servo_parameters.h>

Public Types

using SharedConstPtr = std::shared_ptr< const ServoParameters >
 

Public Member Functions

bool registerSetParameterCallback (const std::string &name, const SetParameterCallbackType &callback) const
 

Static Public Member Functions

static SharedConstPtr makeServoParameters (const rclcpp::Node::SharedPtr &node, const std::string &ns="moveit_servo", bool dynamic_parameters=true)
 
static ServoParameters get (const std::string &ns, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &node_parameters)
 
static std::optional< ServoParametersvalidate (ServoParameters parameters)
 

Public Attributes

const std::string ns
 
bool use_gazebo { false }
 
std::string status_topic { "~/status" }
 
std::string cartesian_command_in_topic { "~/delta_twist_cmds" }
 
std::string joint_command_in_topic { "~/delta_joint_cmds" }
 
std::string robot_link_command_frame { "panda_link0" }
 
std::string command_in_type { "unitless" }
 
double linear_scale { 0.4 }
 
double rotational_scale { 0.8 }
 
double joint_scale { 0.5 }
 
double override_velocity_scaling_factor { 0.0 }
 
std::string command_out_topic { "/panda_arm_controller/joint_trajectory" }
 
double publish_period { 0.034 }
 
std::string command_out_type { "trajectory_msgs/JointTrajectory" }
 
bool publish_joint_positions { true }
 
bool publish_joint_velocities { true }
 
bool publish_joint_accelerations { false }
 
std::string joint_topic { "/joint_states" }
 
std::string smoothing_filter_plugin_name { "online_signal_smoothing::ButterworthFilterPlugin" }
 
std::string move_group_name { "panda_arm" }
 
std::string planning_frame { "panda_link0" }
 
std::string ee_frame_name { "panda_link8" }
 
bool is_primary_planning_scene_monitor = { true }
 
std::string monitored_planning_scene_topic
 
double incoming_command_timeout { 0.1 }
 
int num_outgoing_halt_msgs_to_publish { 4 }
 
bool halt_all_joints_in_joint_mode { true }
 
bool halt_all_joints_in_cartesian_mode { true }
 
double lower_singularity_threshold { 17.0 }
 
double hard_stop_singularity_threshold { 30.0 }
 
double leaving_singularity_threshold_multiplier { 2.0 }
 
double joint_limit_margin { 0.1 }
 
bool low_latency_mode { false }
 
bool check_collisions { true }
 
double collision_check_rate { 10.0 }
 
double self_collision_proximity_threshold { 0.01 }
 
double scene_collision_proximity_threshold { 0.02 }
 

Detailed Description

Definition at line 52 of file servo_parameters.h.

Member Typedef Documentation

◆ SharedConstPtr

Definition at line 54 of file servo_parameters.h.

Member Function Documentation

◆ get()

ServoParameters moveit_servo::ServoParameters::get ( const std::string &  ns,
const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr &  node_parameters 
)
static

Definition at line 267 of file servo_parameters.cpp.

Here is the caller graph for this function:

◆ makeServoParameters()

ServoParameters::SharedConstPtr moveit_servo::ServoParameters::makeServoParameters ( const rclcpp::Node::SharedPtr &  node,
const std::string &  ns = "moveit_servo",
bool  dynamic_parameters = true 
)
static

Declares, reads, and validates parameters used for moveit_servo

Parameters
nodeShared ptr to node that will the parameters will be declared in. Params should be defined in launch/config files
loggerLogger for outputting warnings about the parameters
parametersThe set up parameters that will be updated. After this call, they can be used to start a Servo instance
nsParameter namespace (as loaded in launch files). Defaults to "moveit_servo" but can be changed to allow multiple arms/instances
dynamic_parametersEnable dynamic parameter handling. (default: true)
Returns
std::shared_ptr<ServoParameters> if all parameters were loaded and verified successfully, nullptr otherwise

Definition at line 456 of file servo_parameters.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ registerSetParameterCallback()

bool moveit_servo::ServoParameters::registerSetParameterCallback ( const std::string &  name,
const SetParameterCallbackType callback 
) const
inline

Register a callback for a parameter set event. Note that these callbacks do not change any of the parameters struct. Use a local variable for tracking the state of the dynamic parameter after initial bringup.

Parameters
nameName of parameter (key used for callback in map)
callbackfunction to call when parameter is changed

Definition at line 131 of file servo_parameters.h.

◆ validate()

std::optional< ServoParameters > moveit_servo::ServoParameters::validate ( ServoParameters  parameters)
static

Definition at line 354 of file servo_parameters.cpp.

Here is the caller graph for this function:

Member Data Documentation

◆ cartesian_command_in_topic

std::string moveit_servo::ServoParameters::cartesian_command_in_topic { "~/delta_twist_cmds" }

Definition at line 65 of file servo_parameters.h.

◆ check_collisions

bool moveit_servo::ServoParameters::check_collisions { true }

Definition at line 104 of file servo_parameters.h.

◆ collision_check_rate

double moveit_servo::ServoParameters::collision_check_rate { 10.0 }

Definition at line 105 of file servo_parameters.h.

◆ command_in_type

std::string moveit_servo::ServoParameters::command_in_type { "unitless" }

Definition at line 68 of file servo_parameters.h.

◆ command_out_topic

std::string moveit_servo::ServoParameters::command_out_topic { "/panda_arm_controller/joint_trajectory" }

Definition at line 75 of file servo_parameters.h.

◆ command_out_type

std::string moveit_servo::ServoParameters::command_out_type { "trajectory_msgs/JointTrajectory" }

Definition at line 77 of file servo_parameters.h.

◆ ee_frame_name

std::string moveit_servo::ServoParameters::ee_frame_name { "panda_link8" }

Definition at line 87 of file servo_parameters.h.

◆ halt_all_joints_in_cartesian_mode

bool moveit_servo::ServoParameters::halt_all_joints_in_cartesian_mode { true }

Definition at line 96 of file servo_parameters.h.

◆ halt_all_joints_in_joint_mode

bool moveit_servo::ServoParameters::halt_all_joints_in_joint_mode { true }

Definition at line 95 of file servo_parameters.h.

◆ hard_stop_singularity_threshold

double moveit_servo::ServoParameters::hard_stop_singularity_threshold { 30.0 }

Definition at line 99 of file servo_parameters.h.

◆ incoming_command_timeout

double moveit_servo::ServoParameters::incoming_command_timeout { 0.1 }

Definition at line 93 of file servo_parameters.h.

◆ is_primary_planning_scene_monitor

bool moveit_servo::ServoParameters::is_primary_planning_scene_monitor = { true }

Definition at line 88 of file servo_parameters.h.

◆ joint_command_in_topic

std::string moveit_servo::ServoParameters::joint_command_in_topic { "~/delta_joint_cmds" }

Definition at line 66 of file servo_parameters.h.

◆ joint_limit_margin

double moveit_servo::ServoParameters::joint_limit_margin { 0.1 }

Definition at line 101 of file servo_parameters.h.

◆ joint_scale

double moveit_servo::ServoParameters::joint_scale { 0.5 }

Definition at line 71 of file servo_parameters.h.

◆ joint_topic

std::string moveit_servo::ServoParameters::joint_topic { "/joint_states" }

Definition at line 82 of file servo_parameters.h.

◆ leaving_singularity_threshold_multiplier

double moveit_servo::ServoParameters::leaving_singularity_threshold_multiplier { 2.0 }

Definition at line 100 of file servo_parameters.h.

◆ linear_scale

double moveit_servo::ServoParameters::linear_scale { 0.4 }

Definition at line 69 of file servo_parameters.h.

◆ low_latency_mode

bool moveit_servo::ServoParameters::low_latency_mode { false }

Definition at line 102 of file servo_parameters.h.

◆ lower_singularity_threshold

double moveit_servo::ServoParameters::lower_singularity_threshold { 17.0 }

Definition at line 98 of file servo_parameters.h.

◆ monitored_planning_scene_topic

std::string moveit_servo::ServoParameters::monitored_planning_scene_topic
Initial value:
{
}
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.

Definition at line 89 of file servo_parameters.h.

◆ move_group_name

std::string moveit_servo::ServoParameters::move_group_name { "panda_arm" }

Definition at line 85 of file servo_parameters.h.

◆ ns

const std::string moveit_servo::ServoParameters::ns

Definition at line 57 of file servo_parameters.h.

◆ num_outgoing_halt_msgs_to_publish

int moveit_servo::ServoParameters::num_outgoing_halt_msgs_to_publish { 4 }

Definition at line 94 of file servo_parameters.h.

◆ override_velocity_scaling_factor

double moveit_servo::ServoParameters::override_velocity_scaling_factor { 0.0 }

Definition at line 73 of file servo_parameters.h.

◆ planning_frame

std::string moveit_servo::ServoParameters::planning_frame { "panda_link0" }

Definition at line 86 of file servo_parameters.h.

◆ publish_joint_accelerations

bool moveit_servo::ServoParameters::publish_joint_accelerations { false }

Definition at line 80 of file servo_parameters.h.

◆ publish_joint_positions

bool moveit_servo::ServoParameters::publish_joint_positions { true }

Definition at line 78 of file servo_parameters.h.

◆ publish_joint_velocities

bool moveit_servo::ServoParameters::publish_joint_velocities { true }

Definition at line 79 of file servo_parameters.h.

◆ publish_period

double moveit_servo::ServoParameters::publish_period { 0.034 }

Definition at line 76 of file servo_parameters.h.

◆ robot_link_command_frame

std::string moveit_servo::ServoParameters::robot_link_command_frame { "panda_link0" }

Definition at line 67 of file servo_parameters.h.

◆ rotational_scale

double moveit_servo::ServoParameters::rotational_scale { 0.8 }

Definition at line 70 of file servo_parameters.h.

◆ scene_collision_proximity_threshold

double moveit_servo::ServoParameters::scene_collision_proximity_threshold { 0.02 }

Definition at line 107 of file servo_parameters.h.

◆ self_collision_proximity_threshold

double moveit_servo::ServoParameters::self_collision_proximity_threshold { 0.01 }

Definition at line 106 of file servo_parameters.h.

◆ smoothing_filter_plugin_name

std::string moveit_servo::ServoParameters::smoothing_filter_plugin_name { "online_signal_smoothing::ButterworthFilterPlugin" }

Definition at line 83 of file servo_parameters.h.

◆ status_topic

std::string moveit_servo::ServoParameters::status_topic { "~/status" }

Definition at line 63 of file servo_parameters.h.

◆ use_gazebo

bool moveit_servo::ServoParameters::use_gazebo { false }

Definition at line 62 of file servo_parameters.h.


The documentation for this struct was generated from the following files: