Skip to content

Commit

Permalink
Adjusted accelleration values and joystick scaling.
Browse files Browse the repository at this point in the history
The back right drive is ignored since it makes the other drives crash.
  • Loading branch information
nathan-gt committed Jan 1, 1970
1 parent 1955c02 commit b0296b0
Show file tree
Hide file tree
Showing 8 changed files with 28 additions and 24 deletions.
4 changes: 2 additions & 2 deletions src/rove_bringup/config/joy_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,12 +2,12 @@
ros__parameters:
autorepeat_rate: 20.0 # 0 (publish on change)
coalesce_interval_ms: 50 # 1000ms / 20 (refresh rate in Hz) = 50
deadzone: 0.05
deadzone: 0.2
sticky_buttons: false

/joy_node:
ros__parameters:
autorepeat_rate: 20.0
coalesce_interval_ms: 50
deadzone: 0.05
deadzone: 0.2
sticky_buttons: false
10 changes: 5 additions & 5 deletions src/rove_bringup/config/teleop_joy_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -9,22 +9,22 @@
y: -1 #not set
z: -1 #not set
enable_button: 0 #A
enable_turbo_button: -1 # not set
enable_turbo_button: 1 # not set
require_enable_button: true
scale_angular:
pitch: 0.0
roll: 0.0
yaw: 1.0
yaw: 1.5
scale_angular_turbo:
pitch: 0.0
roll: 0.0
yaw: 1.0
yaw: 2.0
scale_linear:
x: 1.0
x: 1.5
y: 0.0
z: 0.0
scale_linear_turbo:
x: 2.0
y: 0.0
z: 0.0
# publish_stamped_twist: true
# publish_stamped_twist: true
2 changes: 1 addition & 1 deletion src/rove_bringup/config/vn_300.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

vectornav:
ros__parameters:
port: "/dev/ttyUSB0" # TODO: update this for rove
port: "/dev/ttyUSB1" # TODO: update this for rove
baud: 921600
adjust_ros_timestamp: True
reconnect_ms: 500
Expand Down
4 changes: 2 additions & 2 deletions src/rove_bringup/launch/common.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ def generate_launch_description():
# robot_localization_node_global,
#navsat_transform,
twist_mux,
rviz,
#rviz,
teleop,
autonomy,
#autonomy,
])
14 changes: 8 additions & 6 deletions src/rove_bringup/launch/real.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription, RegisterEventHandler, ExecuteProcess
from launch.actions import IncludeLaunchDescription, RegisterEventHandler, ExecuteProcess, TimerAction

from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import Command, PathJoinSubstitution, FindExecutable
Expand Down Expand Up @@ -135,12 +135,14 @@ def create_controller_node(node_name:str):
)

return LaunchDescription([
control_node,
common,
gripper,
joint_state_broadcaster_spawner,
*delayed_controller_nodes,
vectornav,
velodyne,
zed,
control_node,
#TimerAction(period=20.0, actions=[
#gripper,
#vectornav,
#velodyne,
#zed,
#]),
])
13 changes: 7 additions & 6 deletions src/rove_description/config/tracks_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ diff_drive_controller:
open_loop: true
enable_odom_tf: true

cmd_vel_timeout: 0.5
cmd_vel_timeout: 2.0
# publish_limited_velocity: true
# publish_cmd: true
# velocity_rolling_window_size: 10
Expand All @@ -59,15 +59,16 @@ diff_drive_controller:
linear.x.max_velocity: 5.0
linear.x.min_velocity: -5.0
linear.x.max_acceleration: 2.0
linear.x.min_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: 1.0
angular.z.min_velocity: -1.0
angular.z.max_acceleration: 1.0
angular.z.min_acceleration: -1.0
angular.z.max_velocity: 2.0
angular.z.min_velocity: -2.0
angular.z.max_acceleration: 3.0
angular.z.min_acceleration: -3.0
angular.z.max_jerk: 0.0
angular.z.min_jerk: 0.0
angular.z.min_jerk: 0.0
3 changes: 2 additions & 1 deletion src/rove_description/urdf/rove.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,8 @@
<!-- <xacro:rove_ros2_control/> -->
<!-- Put these at -1 to mock the motors if working without the motors -->
<!-- <xacro:odrive_control fl_id="21" rl_id="22" fr_id="23" rr_id="24"/> -->
<xacro:odrive_control fl_id="21" rl_id="22" fr_id="23" rr_id="24"/>
<!-- TODO Fix rr Odrive, it keeps crashing the rest of the drives. IT has been disabled for now. -->
<xacro:odrive_control fl_id="21" rl_id="22" fr_id="23" rr_id="-1"/>


<!-- Insert ovis on top of rove -->
Expand Down
2 changes: 1 addition & 1 deletion src/rove_launch_handler/scripts/launch_script.service
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ After=network.target

[Service]
Environment="ROS_LOG_DIR=/var/log/ros2; ROS_DOMAIN_ID=96"
ExecStart=/bin/bash -c 'source /media/SSD/stable/rove/install/setup.bash; ros2 launch rove_launch_handler launch_handler.launch.py;'
ExecStart=/bin/bash -c 'source /media/SSD/stable/rove/install/setup.bash; ip link set can0 up type can bitrate 500000; ros2 launch rove_launch_handler launch_handler.launch.py;'
RemainAfterExit=no
Restart=on-failure
RestartSec=2s
Expand Down

0 comments on commit b0296b0

Please sign in to comment.