Skip to content

Commit

Permalink
unknown changes
Browse files Browse the repository at this point in the history
  • Loading branch information
davidcalderon03 committed Oct 1, 2023
1 parent fdd42f6 commit a86e017
Show file tree
Hide file tree
Showing 3 changed files with 106 additions and 4 deletions.
68 changes: 68 additions & 0 deletions urc_gazebo/config/my_controllers.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
controller_manager:
ros__parameters:
update_rate: 30
use_sim_time: true

diff_cont:
type: diff_drive_controller/DiffDriveController

joint_broad:
type: joint_state_broadcaster/JointStateBroadcaster

diff_cont:
ros__parameters:

publish_rate: 50.0

base_frame_id: base_link

left_wheel_names: ['left_front_wheel_joint', 'left_center_wheel_joint', 'left_rear_wheel_joint']
right_wheel_names: ['right_front_wheel_joint', 'right_center_wheel_joint', 'right_rear_wheel_joint']
wheel_separation: 0.05
wheel_radius: 0.05

use_stamped_vel: false

# open_loop: false

# wheels_per_side: x
# wheel_separation_multiplier: x
# left_wheel_radius_multiplier: x
# right_wheel_radius_multiplier: x

# odom_frame_id: x
# pose_covariance_diagonal: x
# twist_covariance_diagonal: x
# open_loop: x
# enable_odom_tf: x

# cmd_vel_timeout: x
# publish_limited_velocity: x
# velocity_rolling_window_size: x


# linear.x.has_velocity_limits: false
# linear.x.has_acceleration_limits: false
# linear.x.has_jerk_limits: false
# linear.x.max_velocity: NAN
# linear.x.min_velocity: NAN
# linear.x.max_acceleration: NAN
# linear.x.min_acceleration: NAN
# linear.x.max_jerk: NAN
# linear.x.min_jerk: NAN

# angular.z.has_velocity_limits: false
# angular.z.has_acceleration_limits: false
# angular.z.has_jerk_limits: false
# angular.z.max_velocity: NAN
# angular.z.min_velocity: NAN
# angular.z.max_acceleration: NAN
# angular.z.min_acceleration: NAN
# angular.z.max_jerk: NAN
# angular.z.min_jerk: NAN




# joint_broad:
# ros__parameters:
40 changes: 36 additions & 4 deletions urc_gazebo/urdf/ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -6,15 +6,47 @@
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
<joint name="left_wheel_joint">
<joint name="left_front_wheel_joint">
<command_interface name="velocity">
<param name="min">-10</param>
<param name="max">10</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
<joint name="right_wheel_joint">
<joint name="right_front_wheel_joint">
<command_interface name="velocity">
<param name="min">-10</param>
<param name="max">10</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
<joint name="left_center_wheel_joint">
<command_interface name="velocity">
<param name="min">-10</param>
<param name="max">10</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
<joint name="right_center_wheel_joint">
<command_interface name="velocity">
<param name="min">-10</param>
<param name="max">10</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
<joint name="left_rear_wheel_joint">
<command_interface name="velocity">
<param name="min">-10</param>
<param name="max">10</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
<joint name="right_rear_wheel_joint">
<command_interface name="velocity">
<param name="min">-10</param>
<param name="max">10</param>
Expand All @@ -25,8 +57,8 @@
</ros2_control>

<gazebo>
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
<parameters>$(find articubot_one)/config/my_controllers.yaml</parameters>
<plugin name="gazebo_ros2_control/user" filename="libgazebo_ros2_control.so">
<parameters>$(find urc_gazebo)/config/my_controllers.yaml</parameters>
</plugin>
</gazebo>

Expand Down
2 changes: 2 additions & 0 deletions urc_gazebo/urdf/walli.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@
<xacro:include filename="walli_inertials.xacro"/>
<xacro:include filename="$(find velodyne_description)/urdf/VLP-16.urdf.xacro"/>
<xacro:include filename="walli_arm.urdf"/>
<xacro:include filename="ros2_control.xacro"/>


<!-- Rover Base Link -->
<link name="base_link">
Expand Down

0 comments on commit a86e017

Please sign in to comment.