Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
34 changes: 24 additions & 10 deletions src/description/config/athena_drive_sim_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -14,29 +14,43 @@ controller_manager:

ackermann_steering_controller:
ros__parameters:

# Joint names
rear_wheels_names: ["propulsion_fl_joint", "propulsion_fr_joint"]

front_wheels_names: ["steer_fl_joint", "steer_fr_joint"]

# Vehicle dimensions
wheelbase: 0.8382
front_wheel_track: 0.6604
rear_wheel_track: 0.6604
wheelbase: 0.8382
front_wheels_radius: 0.254
rear_wheels_radius: 0.254

# Steering configuration
front_steering: true

# Control parameters
use_stamped_vel: true
publish_rate: 50.0

odom_frame_id: "odom"
base_frame_id: "base_link"
publish_odom: true
publish_odom_tf: true
open_loop: false
reduce_wheel_speed_until_steering_reached: false
velocity_rolling_window_size: 10
reference_timeout: 0.2

# Frame IDs
base_frame_id: "base_footprint"
odom_frame_id: "odom"

# Odometry configuration
enable_odom_tf: false
position_feedback: false

# Covariance
twist_covariance_diagonal: [0.0, 7.0, 14.0, 21.0, 28.0, 35.0]
pose_covariance_diagonal: [0.0, 7.0, 14.0, 21.0, 28.0, 35.0]


rear_steer_position_controller:
ros__parameters:
joints:
- steer_br_joint
- steer_bl_joint
interface_name: position
interface_name: position
10 changes: 5 additions & 5 deletions src/description/urdf/athena_drive.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -40,15 +40,15 @@
<xacro:description/>


<xacro:imu_sensor parent="base_link">
<origin xyz="0 0 0.0" rpy="0 0 0"/>
<xacro:imu_sensor parent="base_footprint">
<origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
</xacro:imu_sensor>

<xacro:gps_sensor parent="base_link">
<origin xyz="0 0 0.0" rpy="0 0 0"/>
<xacro:gps_sensor parent="base_footprint">
<origin xyz="0.0 0.0 0.0" rpy="0 0 0"/>
</xacro:gps_sensor>

<xacro:ground_truth_odometry/>
<xacro:ground_truth_odometry robot_base_frame="base_footprint"/>

<xacro:depth_camera parent_link="base_link">
<origin xyz="0.75 0 -0.37" rpy="0 0 0"/>
Expand Down
Loading