forked from PickNikRobotics/moveit_pro_empty_ws
-
Notifications
You must be signed in to change notification settings - Fork 7
Expand file tree
/
Copy pathur_servo.yaml
More file actions
64 lines (52 loc) · 3.36 KB
/
ur_servo.yaml
File metadata and controls
64 lines (52 loc) · 3.36 KB
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
59
60
61
62
63
64
###############################################
# Modify all parameters related to servoing here
###############################################
# Enable dynamic parameter updates
enable_parameter_update: true
## 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: 2.0 # Max linear velocity. Meters per publish_period. Unit is [m/s]. Only used for Cartesian commands.
rotational: 3.0 # 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: 2.0
# Default to driving the arm at 50% maximum speed.
override_velocity_scaling_factor: 0.5
## Properties of outgoing commands
publish_period: 0.01 # 1/Nominal publish rate [seconds]
max_expected_latency: 0.1 # delay between sending a command and the robot executing it [seconds]
# What type of topic does your robot driver expect?
# Currently supported are std_msgs/Float64MultiArray or trajectory_msgs/JointTrajectory
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: true
publish_joint_accelerations: false
## Plugins for smoothing outgoing commands
use_smoothing: true
smoothing_filter_plugin_name: "moveit_pro::base::online_signal_smoothing::AccelerationLimitedPlugin"
acceleration_filter_update_period: 0.01 # [seconds] Must match the publish_period parameter
## MoveIt properties
move_group_name: manipulator # Often 'manipulator' or 'arm'
acceleration_filter_planning_group_name: manipulator # Often 'manipulator' or 'arm'
is_primary_planning_scene_monitor: false # The MoveGroup node maintains the planning scene, so Servo needs to get its world info from there.
monitored_planning_scene_topic: /monitored_planning_scene
## Stopping behaviour
incoming_command_timeout: 0.1 # 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: 50.0 # Stop when the condition number hits this
joint_limit_margins: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] # added as a buffer to joint limits [radians]. If moving quickly, make this larger.
## Topic names
cartesian_command_in_topic: ~/delta_twist_cmds # Topic for incoming Cartesian twist commands
joint_command_in_topic: ~/delta_joint_cmds # Topic for incoming joint angle commands
joint_topic: /joint_states
status_topic: ~/status # Publish status to this topic
command_out_topic: /servo_controller/joint_trajectory # Publish outgoing commands here
## Collision checking for the entire robot body
check_collisions: true # Check collisions?
check_octomap_collisions: false # Check collisions with octomap?
collision_check_rate: 10.0 # [Hz] Collision-checking can easily bog down a CPU if done too often.
self_collision_proximity_threshold: 0.006 # Start decelerating when a self-collision is this far [m]
scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m]