servo not working due to an error - moveit thinks the robot is in collision all the time and with twist cmd in addition very close to a singularity
This commit is contained in:
parent
082616eb7e
commit
6bdeba687e
@ -7,8 +7,8 @@ use_intra_process_comms : true
|
||||
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.6 # Max linear velocity. Meters per publish_period. Unit is [m/s]. Only used for Cartesian commands.
|
||||
rotational: 0.3 # Max angular velocity. Rads per publish_period. Unit is [rad/s]. Only used for Cartesian commands.
|
||||
linear: 0.05 # Max linear velocity. Meters per publish_period. Unit is [m/s]. Only used for Cartesian commands.
|
||||
rotational: 0.05 # 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
|
||||
# This is a fudge factor to account for any latency in the system, e.g. network latency or poor low-level
|
||||
@ -22,11 +22,11 @@ low_latency_mode: false # Set this to true to publish as soon as an incoming Tw
|
||||
|
||||
# What type of topic does your robot driver expect?
|
||||
# Currently supported are std_msgs/Float64MultiArray or trajectory_msgs/JointTrajectory
|
||||
command_out_type: std_msgs/Float64MultiArray
|
||||
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_velocities: true
|
||||
publish_joint_accelerations: false
|
||||
|
||||
## Plugins for smoothing outgoing commands
|
||||
@ -50,9 +50,9 @@ incoming_command_timeout: 0.1 # Stop servoing if X seconds elapse without a ne
|
||||
num_outgoing_halt_msgs_to_publish: 4
|
||||
|
||||
## Configure handling of singularities and joint limits
|
||||
lower_singularity_threshold: 100.0 # Start decelerating when the condition number hits this (close to singularity)
|
||||
hard_stop_singularity_threshold: 200.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.
|
||||
lower_singularity_threshold: 50.0 # Start decelerating when the condition number hits this (close to singularity)
|
||||
hard_stop_singularity_threshold: 100.0 # Stop when the condition number hits this
|
||||
joint_limit_margin: 0.05 # 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
|
||||
@ -63,14 +63,14 @@ command_out_topic: /forward_position_controller/commands # Publish outgoing comm
|
||||
|
||||
## 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.
|
||||
collision_check_rate: 10.0 # [Hz] Collision-checking can easily bog down a CPU if done too often.
|
||||
# Two collision check algorithms are available:
|
||||
# "threshold_distance" begins slowing down when nearer than a specified distance. Good if you want to tune collision thresholds manually.
|
||||
# "stop_distance" stops if a collision is nearer than the worst-case stopping distance and the distance is decreasing. Requires joint acceleration limits
|
||||
collision_check_type: threshold_distance
|
||||
# Parameters for "threshold_distance"-type collision checking
|
||||
self_collision_proximity_threshold: 0.01 # 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]
|
||||
self_collision_proximity_threshold: 0.005 # Start decelerating when a self-collision is this far [m]
|
||||
scene_collision_proximity_threshold: 0.01 # Start decelerating when a scene collision is this far [m]
|
||||
# Parameters for "stop_distance"-type collision checking
|
||||
collision_distance_safety_factor: 1000.0 # Must be >= 1. A large safety factor is recommended to account for latency
|
||||
min_allowable_collision_distance: 0.01 # Stop if a collision is closer than this [m]
|
||||
collision_distance_safety_factor: 100.0 # Must be >= 1. A large safety factor is recommended to account for latency
|
||||
min_allowable_collision_distance: 0.005 # Stop if a collision is closer than this [m]
|
||||
|
@ -58,7 +58,7 @@ class PS5ControllerNode(Node):
|
||||
self.get_logger().info(f'Mode switched to: {self.mode}')
|
||||
self.last_button_state = current_button_state
|
||||
|
||||
left_trigger = (msg.axes[2] - 1) / - 2.0
|
||||
left_trigger = (msg.axes[4] - 1) / - 2.0
|
||||
right_trigger = (msg.axes[5] - 1) / - 2.0
|
||||
|
||||
# Process control input based on current mode
|
||||
|
Loading…
Reference in New Issue
Block a user