Skip to content

Commit cd92509

Browse files
BorgesJVTdestogl
authored andcommitted
applying review suggestions
1 parent 324535e commit cd92509

File tree

5 files changed

+76
-43
lines changed

5 files changed

+76
-43
lines changed

ros2_control_demo_hardware/include/ros2_control_demo_hardware/diffbot_system.hpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2020 ros2_control Development Team
1+
// Copyright 2021 ros2_control Development Team
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -20,14 +20,13 @@
2020
#include <string>
2121
#include <vector>
2222

23-
#include "rclcpp/macros.hpp"
24-
2523
#include "hardware_interface/base_interface.hpp"
2624
#include "hardware_interface/system_interface.hpp"
2725
#include "hardware_interface/handle.hpp"
2826
#include "hardware_interface/hardware_info.hpp"
2927
#include "hardware_interface/types/hardware_interface_return_values.hpp"
3028
#include "hardware_interface/types/hardware_interface_status_values.hpp"
29+
#include "rclcpp/macros.hpp"
3130
#include "ros2_control_demo_hardware/visibility_control.h"
3231

3332
using hardware_interface::return_type;

ros2_control_demo_robot/controllers/diffbot_diff_drive_controller.yaml

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,8 @@ controller_manager:
22
ros__parameters:
33
update_rate: 2 # Hz
44

5+
joint_state_controller:
6+
type: joint_state_controller/JointStateController
57
diffbot_base_controller:
68
type: diff_drive_controller/DiffDriveController
79

ros2_control_demo_robot/description/diffbot/diffbot.urdf.xacro

Lines changed: 69 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
33

4-
<xacro:macro name="diffbot" params="parent prefix *origin">
4+
<xacro:macro name="diffbot" params="prefix">
55

66
<!-- Constants for robot dimensions -->
77
<xacro:property name="PI" value="3.1415926535897931"/>
@@ -12,14 +12,10 @@
1212
<xacro:property name="wheel_mass" value="0.3" /> <!-- arbitrary value for wheel mass -->
1313
<xacro:property name="wheel_len" value="0.020" />
1414
<xacro:property name="wheel_radius" value="0.015" />
15+
<xacro:property name="caster_wheel_mass" value="0.1" /> <!-- arbitrary value for caster wheel mass -->
16+
<xacro:property name="caster_wheel_radius" value="0.015" />
1517
<xacro:property name="z_offset" value="-${base_height/2}" /> <!-- Space btw top of beam and the each joint -->
1618

17-
<joint name="${prefix}base_joint" type="fixed">
18-
<xacro:insert_block name="origin" />
19-
<parent link="${parent}"/>
20-
<child link="${prefix}base_link" />
21-
</joint>
22-
2319
<!-- Base Link -->
2420
<link name="${prefix}base_link">
2521
<collision>
@@ -117,6 +113,72 @@
117113
</inertial>
118114
</link>
119115

116+
<joint name="${prefix}caster_frontal_wheel_joint" type="fixed">
117+
<parent link="${prefix}base_link"/>
118+
<child link="${prefix}caster_frontal_wheel"/>
119+
<origin xyz="${base_width/2 - caster_wheel_radius} 0 ${z_offset}" rpy="0 0 0"/>
120+
</joint>
121+
122+
<!-- caster frontal wheel Link -->
123+
<link name="${prefix}caster_frontal_wheel">
124+
<collision>
125+
<origin xyz="0 0 0" rpy="0 0 0"/>
126+
<geometry>
127+
<sphere radius="${caster_wheel_radius}"/>
128+
</geometry>
129+
</collision>
130+
131+
<visual>
132+
<origin xyz="0 0 0" rpy="0 0 0"/>
133+
<geometry>
134+
<sphere radius="${caster_wheel_radius}"/>
135+
</geometry>
136+
<material name="white"/>
137+
</visual>
138+
139+
<inertial>
140+
<origin xyz="0 0 0" rpy="0 0 0"/>
141+
<mass value="${caster_wheel_mass}"/>
142+
<inertia
143+
ixx="${caster_wheel_mass * 0.4 * (caster_wheel_radius * caster_wheel_radius)}" ixy="0.0" ixz="0.0"
144+
iyy="${caster_wheel_mass * 0.4 * (caster_wheel_radius * caster_wheel_radius)}" iyz="0.0"
145+
izz="${caster_wheel_mass * 0.4 * (caster_wheel_radius * caster_wheel_radius)}"/>
146+
</inertial>
147+
</link>
148+
149+
<joint name="${prefix}caster_rear_wheel_joint" type="fixed">
150+
<parent link="${prefix}base_link"/>
151+
<child link="${prefix}caster_rear_wheel"/>
152+
<origin xyz="${-base_width/2 + caster_wheel_radius} 0 ${z_offset}" rpy="0 0 0"/>
153+
</joint>
154+
155+
<!-- caster rear wheel Link -->
156+
<link name="${prefix}caster_rear_wheel">
157+
<collision>
158+
<origin xyz="0 0 0" rpy="0 0 0"/>
159+
<geometry>
160+
<sphere radius="${caster_wheel_radius}"/>
161+
</geometry>
162+
</collision>
163+
164+
<visual>
165+
<origin xyz="0 0 0" rpy="0 0 0"/>
166+
<geometry>
167+
<sphere radius="${caster_wheel_radius}"/>
168+
</geometry>
169+
<material name="white"/>
170+
</visual>
171+
172+
<inertial>
173+
<origin xyz="0 0 0" rpy="0 0 0"/>
174+
<mass value="${caster_wheel_mass}"/>
175+
<inertia
176+
ixx="${caster_wheel_mass * 0.4 * (caster_wheel_radius * caster_wheel_radius)}" ixy="0.0" ixz="0.0"
177+
iyy="${caster_wheel_mass * 0.4 * (caster_wheel_radius * caster_wheel_radius)}" iyz="0.0"
178+
izz="${caster_wheel_mass * 0.4 * (caster_wheel_radius * caster_wheel_radius)}"/>
179+
</inertial>
180+
</link>
181+
120182
</xacro:macro>
121183

122184
</robot>

ros2_control_demo_robot/description/diffbot/diffbot_system.ros2_control.xacro

Lines changed: 2 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -11,44 +11,23 @@
1111
<param name="example_param_hw_slowdown">2.0</param>
1212
</hardware>
1313
<joint name="left_wheel_joint">
14-
<state_interface name="position"/>
1514
<command_interface name="velocity">
1615
<param name="min">-1</param>
1716
<param name="max">1</param>
1817
</command_interface>
18+
<state_interface name="position"/>
1919
<state_interface name="velocity"/>
2020
</joint>
2121
<joint name="right_wheel_joint">
22-
<state_interface name="position"/>
2322
<command_interface name="velocity">
2423
<param name="min">-1</param>
2524
<param name="max">1</param>
2625
</command_interface>
26+
<state_interface name="position"/>
2727
<state_interface name="velocity"/>
2828
</joint>
2929
</ros2_control>
3030

31-
<!-- <ros2_control name="TestActuatorHardwareLeft" type="actuator">
32-
<hardware>
33-
<plugin>test_actuator</plugin>
34-
</hardware>
35-
<joint name="left_wheel_joint">
36-
<state_interface name="position"/>
37-
<command_interface name="velocity"/>
38-
<state_interface name="velocity"/>
39-
</joint>
40-
</ros2_control>
41-
<ros2_control name="TestActuatorHardwareRight" type="actuator">
42-
<hardware>
43-
<plugin>test_actuator</plugin>
44-
</hardware>
45-
<joint name="right_wheel_joint">
46-
<state_interface name="position"/>
47-
<command_interface name="velocity"/>
48-
<state_interface name="velocity"/>
49-
</joint>
50-
</ros2_control> -->
51-
5231
</xacro:macro>
5332

5433
</robot>

ros2_control_demo_robot/description/diffbot_system.urdf.xacro

Lines changed: 1 addition & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,6 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/diffbot_de
66
-->
77
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="2dof_robot">
88

9-
<!-- Import diffbot macro -->
109
<xacro:include filename="diffbot/diffbot.urdf.xacro" />
1110
<!-- <xacro:include filename="$(find ros2_control_demo_robot)/description/diffbot/diffbot.urdf.xacro" /> -->
1211

@@ -22,15 +21,7 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/diffbot_de
2221
<xacro:include filename="diffbot/diffbot_system.ros2_control.xacro" />
2322
<!-- <xacro:include filename="$(find ros2_control_demo_robot)/description/diffbot/diffbot_system.ros2_control.xacro" /> -->
2423

25-
<!-- Used for fixing robot -->
26-
<link name="world"/>
27-
<gazebo reference="world">
28-
<static>true</static>
29-
</gazebo>
30-
31-
<xacro:diffbot parent="world" prefix="">
32-
<origin xyz="0 0 0" rpy="0 0 0" />
33-
</xacro:diffbot>
24+
<xacro:diffbot prefix="" />
3425

3526
<xacro:diffbot_gazebo prefix="" />
3627

0 commit comments

Comments
 (0)