Skip to content

Commit

Permalink
Fix odom drift
Browse files Browse the repository at this point in the history
  • Loading branch information
MarqRazz committed Oct 27, 2023
1 parent 1d0e9a6 commit aaaf42e
Show file tree
Hide file tree
Showing 8 changed files with 57 additions and 20 deletions.
7 changes: 3 additions & 4 deletions .docker/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -78,14 +78,13 @@ RUN echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable jammy main"
RUN mkdir -p /root/c3pzero_ws/src
WORKDIR /root/c3pzero_ws/src
COPY ./ ./c3pzero/
# RUN vcs import < ./c3pzero/c3pzero.repos # I prefer to manage my repos on the host
RUN vcs import < ./c3pzero/c3pzero.repos
WORKDIR /root/c3pzero_ws
# hadolint ignore=SC1091
RUN source /opt/ros/humble/setup.bash \
&& apt-get update -y \
&& apt-get upgrade -y \
# TODO correct rosdep command from requiring -r command (its still looking for robotiq_description)
&& rosdep install --from-paths src --ignore-src --rosdistro "$ROS_DISTRO" -y -r \
&& rosdep install --from-paths src --ignore-src --rosdistro "$ROS_DISTRO" -y \
&& rm -rf /var/lib/apt/lists/*

# Use CycloneDDS as the default but also setup Fast DDS to support NVIDIA Isaac Sim.
Expand All @@ -97,7 +96,7 @@ COPY ./.docker/cyclonedds_localhost.xml /root/.ros/cyclonedds_localhost.xml
ENV FASTRTPS_DEFAULT_PROFILES_FILE=/root/.ros/fastdds.xml

# Pre-download the gazebo world so it doesn't have to on the first sim launch
RUN ign fuel download -v 4 -u https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Depot
RUN ign fuel download -v 4 -u https://fuel.gazebosim.org/1.0/OpenRobotics/models/Depot

# Set up the entrypoint for both container start and interactive terminals.
COPY ./.docker/ros_entrypoint.sh /root/.ros/
Expand Down
8 changes: 5 additions & 3 deletions c300/c300_bringup/config/c300_gz_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,14 @@ diff_drive_base_controller:
ros__parameters:
left_wheel_names: ["drivewhl_l_joint"]
right_wheel_names: ["drivewhl_r_joint"]
wheels_per_side: 1

wheel_separation: 0.539
wheel_separation: 0.54
wheel_radius: 0.1715

wheel_separation_multiplier: 1.0
left_wheel_radius_multiplier: 0.89 # TODO figure out why this multiplier needs to be offset!
right_wheel_radius_multiplier: 0.89
left_wheel_radius_multiplier: 1.0 # 0.89 # TODO figure out why this multiplier needs to be offset!
right_wheel_radius_multiplier: 1.0 # 0.89

publish_rate: 50.0
odom_frame_id: odom
Expand All @@ -27,6 +28,7 @@ diff_drive_base_controller:
twist_covariance_diagonal: [0.001, 0.0, 0.0, 0.0, 0.0, 0.01]

open_loop: false
position_feedback: true
enable_odom_tf: true

cmd_vel_timeout: 0.5
Expand Down
8 changes: 5 additions & 3 deletions c300/c300_bringup/config/c300_isaac_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -12,13 +12,14 @@ diff_drive_base_controller:
ros__parameters:
left_wheel_names: ["drivewhl_l_joint"]
right_wheel_names: ["drivewhl_r_joint"]
wheels_per_side: 1

wheel_separation: 0.539
wheel_separation: 0.54
wheel_radius: 0.1715

wheel_separation_multiplier: 1.0
left_wheel_radius_multiplier: 0.965 # TODO figure out why this multiplier needs to be offset!
right_wheel_radius_multiplier: 0.965
left_wheel_radius_multiplier: 1.0 # 0.965 # TODO figure out why this multiplier needs to be offset!
right_wheel_radius_multiplier: 1.0 # 0.965

publish_rate: 50.0
odom_frame_id: odom
Expand All @@ -27,6 +28,7 @@ diff_drive_base_controller:
twist_covariance_diagonal: [0.001, 0.0, 0.0, 0.0, 0.0, 0.01]

open_loop: false
position_feedback: true
enable_odom_tf: true

cmd_vel_timeout: 0.5
Expand Down
1 change: 1 addition & 0 deletions c300/c300_bringup/launch/isaac_c300.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,7 @@ def generate_launch_description():
prefix = LaunchConfiguration("prefix")
diff_drive_controller = LaunchConfiguration("diff_drive_controller")
launch_rviz = LaunchConfiguration("launch_rviz")
sim_isaac = LaunchConfiguration("sim_isaac")
use_sim_time = LaunchConfiguration("use_sim_time")

robot_controllers = PathJoinSubstitution(
Expand Down
10 changes: 7 additions & 3 deletions c3pzero.repos
Original file line number Diff line number Diff line change
Expand Up @@ -5,15 +5,19 @@ repositories:
version: main
ros2_kortex:
type: git
url: git@github.com:Kinovarobotics/ros2_kortex.git
url: https://github.com/Kinovarobotics/ros2_kortex.git
version: main
ros2_controllers:
type: git
url: https://github.com/MarqRazz/ros2_controllers.git
version: fix_diff_drive_odom
realsense-ros:
type: git
url: git@github.com:MarqRazz/realsense-ros.git
url: https://github.com/MarqRazz/realsense-ros.git
version: ros2-development
ros2_robotiq_gripper:
type: git
url: git@github.com:PickNikRobotics/ros2_robotiq_gripper.git
url: https://github.com/PickNikRobotics/ros2_robotiq_gripper.git
version: main
serial:
type: git
Expand Down
8 changes: 5 additions & 3 deletions c3pzero/c3pzero_bringup/config/c3pzero_gz_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -18,21 +18,23 @@ diff_drive_base_controller:
ros__parameters:
left_wheel_names: ["drivewhl_l_joint"]
right_wheel_names: ["drivewhl_r_joint"]
wheels_per_side: 1

wheel_separation: 0.540
wheel_radius: 0.1715

wheel_separation_multiplier: 1.0
left_wheel_radius_multiplier: 1.0
right_wheel_radius_multiplier: 1.0
left_wheel_radius_multiplier: 1.0 # 0.89 # TODO figure out why this multiplier needs to be offset!
right_wheel_radius_multiplier: 1.0 # 0.89

publish_rate: 50.0
odom_frame_id: odom
base_frame_id: base_link
pose_covariance_diagonal : [0.001, 0.001, 0.0, 0.0, 0.0, 0.01]
twist_covariance_diagonal: [0.001, 0.0, 0.0, 0.0, 0.0, 0.01]

open_loop: true
open_loop: false
position_feedback: true
enable_odom_tf: true

cmd_vel_timeout: 0.5
Expand Down
10 changes: 6 additions & 4 deletions c3pzero/c3pzero_bringup/config/c3pzero_isaac_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -18,21 +18,23 @@ diff_drive_base_controller:
ros__parameters:
left_wheel_names: ["drivewhl_l_joint"]
right_wheel_names: ["drivewhl_r_joint"]
wheels_per_side: 1

wheel_separation: 0.540
wheel_separation: 0.54
wheel_radius: 0.1715

wheel_separation_multiplier: 1.0
left_wheel_radius_multiplier: 1.0
right_wheel_radius_multiplier: 1.0
left_wheel_radius_multiplier: 1.0 # 0.965 # TODO figure out why this multiplier needs to be offset!
right_wheel_radius_multiplier: 1.0 # 0.965

publish_rate: 50.0
odom_frame_id: odom
base_frame_id: base_link
pose_covariance_diagonal : [0.001, 0.001, 0.0, 0.0, 0.0, 0.01]
twist_covariance_diagonal: [0.001, 0.0, 0.0, 0.0, 0.0, 0.01]

open_loop: true
open_loop: false
position_feedback: true
enable_odom_tf: true

cmd_vel_timeout: 0.5
Expand Down
25 changes: 25 additions & 0 deletions c3pzero_ssh.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
repositories:
topic_based_ros2_control:
type: git
url: [email protected]:PickNikRobotics/topic_based_ros2_control.git
version: main
ros2_kortex:
type: git
url: [email protected]:Kinovarobotics/ros2_kortex.git
version: main
ros2_controllers:
type: git
url: [email protected]:MarqRazz/ros2_controllers.git
version: fix_diff_drive_odom
realsense-ros:
type: git
url: [email protected]:MarqRazz/realsense-ros.git
version: ros2-development
ros2_robotiq_gripper:
type: git
url: [email protected]:PickNikRobotics/ros2_robotiq_gripper.git
version: main
serial:
type: git
url: https://github.com/tylerjw/serial.git
version: ros2

0 comments on commit aaaf42e

Please sign in to comment.