Skip to content

Commit

Permalink
adjust velocity and rotation settings
Browse files Browse the repository at this point in the history
  • Loading branch information
IliTheButterfly committed Jun 9, 2024
1 parent 1596926 commit e258810
Show file tree
Hide file tree
Showing 3 changed files with 20 additions and 34 deletions.
8 changes: 4 additions & 4 deletions src/rove_bringup/config/teleop_joy_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -14,17 +14,17 @@
scale_angular:
pitch: 0.0
roll: 0.0
yaw: 200.0
yaw: 1.0
scale_angular_turbo:
pitch: 0.0
roll: 0.0
yaw: 300.0
yaw: 1.0
scale_linear:
x: 50.0
x: 1.0
y: 0.0
z: 0.0
scale_linear_turbo:
x: 100.0
x: 2.0
y: 0.0
z: 0.0
# publish_stamped_twist: true
4 changes: 2 additions & 2 deletions src/rove_bringup/launch/real.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -155,6 +155,6 @@ def create_controller_node(node_name:str):
common,
joint_state_broadcaster_spawner,
*delayed_controller_nodes,
vectornav,
velodyne,
# vectornav,
# velodyne,
])
42 changes: 14 additions & 28 deletions src/rove_description/config/tracks_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -31,18 +31,18 @@ diff_drive_controller:
# right_wheel_names: ["track_fr_j"]

wheel_separation: 0.230
wheel_radius: 0.220
wheel_radius: 0.11

wheel_separation_multiplier: 1.0
left_wheel_radius_multiplier: -1.0
right_wheel_radius_multiplier: 1.0
wheel_separation_multiplier: 10.0
left_wheel_radius_multiplier: -0.0325
right_wheel_radius_multiplier: 0.0325

publish_rate: 20.0
odom_frame_id: odom
# allow_multiple_cmd_vel_publishers: true
base_frame_id: base_link
# pose_covariance_diagonal : [0.001, 0.001, 0.001, 0.001, 0.001, 0.01]
# twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.01]
pose_covariance_diagonal : [0.001, 0.001, 0.001, 0.001, 0.001, 0.01]
twist_covariance_diagonal: [0.001, 0.001, 0.001, 0.001, 0.001, 0.01]

open_loop: true
enable_odom_tf: true
Expand All @@ -53,35 +53,21 @@ diff_drive_controller:
# velocity_rolling_window_size: 10
use_stamped_vel: false

# Velocity and acceleration limits
# Whenever a min_* is unspecified, default to -max_*
linear.x.has_velocity_limits: true
linear.x.has_acceleration_limits: true
linear.x.has_jerk_limits: false
linear.x.max_velocity: 100.0
# linear.x.min_velocity: -1.0
linear.x.max_acceleration: 200.0
linear.x.max_velocity: 5.0
linear.x.min_velocity: -5.0
linear.x.max_acceleration: 2.0
linear.x.max_jerk: 0.0
linear.x.min_jerk: 0.0

angular.z.has_velocity_limits: true
angular.z.has_acceleration_limits: true
angular.z.has_jerk_limits: false
angular.z.max_velocity: 500.0
# angular.z.min_velocity: -1.0
angular.z.max_acceleration: 800.0
# angular.z.min_acceleration: -1.0
angular.z.max_velocity: 1.0
angular.z.min_velocity: -1.0
angular.z.max_acceleration: 1.0
angular.z.min_acceleration: -1.0
angular.z.max_jerk: 0.0
angular.z.min_jerk: 0.0

# left_track_controller:
# ros__parameters:
# track_joint_name: track_l_j
# front_joint: track_fl_j
# back_joint: track_rl_j

# right_track_controller:
# ros__parameters:
# track_joint_name: track_r_j
# front_joint: track_fr_j
# back_joint: track_rr_j
angular.z.min_jerk: 0.0

0 comments on commit e258810

Please sign in to comment.