forked from moveit/moveit2
-
Notifications
You must be signed in to change notification settings - Fork 0
/
servo_settings.yaml
58 lines (47 loc) · 3.16 KB
/
servo_settings.yaml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
###############################################
# Modify all parameters related to servoing here
###############################################
## Properties of incoming commands
command_in_type: "speed_units" # "unitless"> in the range [-1:1], as if from joystick. "speed_units"> cmds are in m/s and rad/s
scale:
# Scale parameters are only used if command_in_type=="unitless"
linear: 0.003 # Max linear velocity. Meters per publish_period. Unit is [m/s]. Only used for Cartesian commands.
rotational: 0.006 # Max angular velocity. Rads per publish_period. Unit is [rad/s]. Only used for Cartesian commands.
# Max joint angular/linear velocity. Rads or Meters per publish period. Only used for joint commands on joint_command_in_topic.
joint: 0.01
## Properties of outgoing commands
low_latency_mode: false # Set this to true to tie the output rate to the input rate
publish_period: 0.01 # 1/Nominal publish rate [seconds]
# What type of topic does your robot driver expect?
# Currently supported are std_msgs/Float64MultiArray (for ros_control JointGroupVelocityController or JointGroupPositionController)
# or trajectory_msgs/JointTrajectory (for Universal Robots and other non-ros_control robots)
command_out_type: trajectory_msgs/JointTrajectory
# What to publish? Can save some bandwidth as most robots only require positions or velocities
publish_joint_positions: true
publish_joint_velocities: false
publish_joint_accelerations: false
## Plugins for smoothing outgoing commands
smoothing_filter_plugin_name: "online_signal_smoothing::ButterworthFilterPlugin"
## MoveIt properties
move_group_name: panda_arm # Often 'manipulator' or 'arm'
planning_frame: panda_link0 # The MoveIt planning frame. Often 'panda_link0' or 'world'
## Other frames
ee_frame_name: panda_link7 # The name of the end effector link, used to return the EE pose
robot_link_command_frame: panda_link0 # commands must be given in the frame of a robot link. Usually either the base or end effector
## Stopping behaviour
incoming_command_timeout: 1.0 # Stop servoing if X seconds elapse without a new command
## Configure handling of singularities and joint limits
lower_singularity_threshold: 30.0 # Start decelerating when the condition number hits this (close to singularity)
hard_stop_singularity_threshold: 90.0 # Stop when the condition number hits this
joint_limit_margin: 0.1 # added as a buffer to joint limits [radians]. If moving quickly, make this larger.
## Topic names
cartesian_command_in_topic: servo_node/delta_twist_cmds # Topic for incoming Cartesian twist commands
joint_command_in_topic: servo_node/delta_joint_cmds # Topic for incoming joint angle commands
joint_topic: joint_states
status_topic: servo_node/status # Publish status to this topic
command_out_topic: servo_node/command # Publish outgoing commands here
## Collision checking for the entire robot body
check_collisions: true # Check collisions?
collision_check_rate: 5.0 # [Hz] Collision-checking can easily bog down a CPU if done too often.
self_collision_proximity_threshold: 0.01 # Start decelerating when a collision is this far [m]
scene_collision_proximity_threshold: 0.03 # Start decelerating when a collision is this far [m]