#include <servo_parameters.h>
Definition at line 52 of file servo_parameters.h.
◆ SharedConstPtr
◆ get()
ServoParameters moveit_servo::ServoParameters::get |
( |
const std::string & |
ns, |
|
|
const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & |
node_parameters |
|
) |
| |
|
static |
◆ 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
-
node | Shared ptr to node that will the parameters will be declared in. Params should be defined in launch/config files |
logger | Logger for outputting warnings about the parameters |
parameters | The set up parameters that will be updated. After this call, they can be used to start a Servo instance |
ns | Parameter namespace (as loaded in launch files). Defaults to "moveit_servo" but can be changed to allow multiple arms/instances |
dynamic_parameters | Enable 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.
◆ 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
-
name | Name of parameter (key used for callback in map) |
callback | function to call when parameter is changed |
Definition at line 131 of file servo_parameters.h.
◆ validate()
◆ cartesian_command_in_topic
std::string moveit_servo::ServoParameters::cartesian_command_in_topic { "~/delta_twist_cmds" } |
◆ check_collisions
bool moveit_servo::ServoParameters::check_collisions { true } |
◆ collision_check_rate
double moveit_servo::ServoParameters::collision_check_rate { 10.0 } |
◆ command_in_type
std::string moveit_servo::ServoParameters::command_in_type { "unitless" } |
◆ command_out_topic
std::string moveit_servo::ServoParameters::command_out_topic { "/panda_arm_controller/joint_trajectory" } |
◆ command_out_type
std::string moveit_servo::ServoParameters::command_out_type { "trajectory_msgs/JointTrajectory" } |
◆ ee_frame_name
std::string moveit_servo::ServoParameters::ee_frame_name { "panda_link8" } |
◆ halt_all_joints_in_cartesian_mode
bool moveit_servo::ServoParameters::halt_all_joints_in_cartesian_mode { true } |
◆ halt_all_joints_in_joint_mode
bool moveit_servo::ServoParameters::halt_all_joints_in_joint_mode { true } |
◆ hard_stop_singularity_threshold
double moveit_servo::ServoParameters::hard_stop_singularity_threshold { 30.0 } |
◆ incoming_command_timeout
double moveit_servo::ServoParameters::incoming_command_timeout { 0.1 } |
◆ is_primary_planning_scene_monitor
bool moveit_servo::ServoParameters::is_primary_planning_scene_monitor = { true } |
◆ joint_command_in_topic
std::string moveit_servo::ServoParameters::joint_command_in_topic { "~/delta_joint_cmds" } |
◆ joint_limit_margin
double moveit_servo::ServoParameters::joint_limit_margin { 0.1 } |
◆ joint_scale
double moveit_servo::ServoParameters::joint_scale { 0.5 } |
◆ joint_topic
std::string moveit_servo::ServoParameters::joint_topic { "/joint_states" } |
◆ leaving_singularity_threshold_multiplier
double moveit_servo::ServoParameters::leaving_singularity_threshold_multiplier { 2.0 } |
◆ linear_scale
double moveit_servo::ServoParameters::linear_scale { 0.4 } |
◆ low_latency_mode
bool moveit_servo::ServoParameters::low_latency_mode { false } |
◆ lower_singularity_threshold
double moveit_servo::ServoParameters::lower_singularity_threshold { 17.0 } |
◆ 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" } |
◆ ns
const std::string moveit_servo::ServoParameters::ns |
◆ num_outgoing_halt_msgs_to_publish
int moveit_servo::ServoParameters::num_outgoing_halt_msgs_to_publish { 4 } |
◆ override_velocity_scaling_factor
double moveit_servo::ServoParameters::override_velocity_scaling_factor { 0.0 } |
◆ planning_frame
std::string moveit_servo::ServoParameters::planning_frame { "panda_link0" } |
◆ publish_joint_accelerations
bool moveit_servo::ServoParameters::publish_joint_accelerations { false } |
◆ publish_joint_positions
bool moveit_servo::ServoParameters::publish_joint_positions { true } |
◆ publish_joint_velocities
bool moveit_servo::ServoParameters::publish_joint_velocities { true } |
◆ publish_period
double moveit_servo::ServoParameters::publish_period { 0.034 } |
◆ robot_link_command_frame
std::string moveit_servo::ServoParameters::robot_link_command_frame { "panda_link0" } |
◆ rotational_scale
double moveit_servo::ServoParameters::rotational_scale { 0.8 } |
◆ scene_collision_proximity_threshold
double moveit_servo::ServoParameters::scene_collision_proximity_threshold { 0.02 } |
◆ self_collision_proximity_threshold
double moveit_servo::ServoParameters::self_collision_proximity_threshold { 0.01 } |
◆ smoothing_filter_plugin_name
std::string moveit_servo::ServoParameters::smoothing_filter_plugin_name { "online_signal_smoothing::ButterworthFilterPlugin" } |
◆ status_topic
std::string moveit_servo::ServoParameters::status_topic { "~/status" } |
◆ use_gazebo
bool moveit_servo::ServoParameters::use_gazebo { false } |
The documentation for this struct was generated from the following files: