Skip to content

Commit 8e40bf5

Browse files
committed
cherry pick wheel velocity limit fix for ros kilted
1 parent 9781841 commit 8e40bf5

File tree

3 files changed

+7
-6
lines changed

3 files changed

+7
-6
lines changed

curt_mini/models/curt_mini/properties.xacro

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,8 @@
77

88
<!-- robot limits -->
99
<xacro:property name="max_effort" value="50.0" />
10-
<xacro:property name="max_velocity" value="5.0" />
10+
<!-- joint limit for wheels, radian/second -->
11+
<xacro:property name="max_velocity" value="20.0" />
1112
<xacro:property name="wheel_radius" value="0.13" />
1213
<xacro:property name="wheel_width" value="0.08" />
1314

curt_mini/models/curt_mini/robot.urdf.xacro

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@
6666
<child link="front_right_wheel" />
6767
<axis xyz="0 -1 0" />
6868
<dynamics damping="1.0" />
69-
<limit effort="${max_effort}" velocity="${max_velocity}" />
69+
<limit effort="${max_effort}" velocity="${max_wheel_velocity}" />
7070
</joint>
7171
<xacro:wheel_transmissions prefix="front_right_motor" />
7272

@@ -98,7 +98,7 @@
9898
<child link="front_left_wheel" />
9999
<axis xyz="0 -1 0" />
100100
<dynamics damping="1.0" />
101-
<limit effort="${max_effort}" velocity="${max_velocity}" />
101+
<limit effort="${max_effort}" velocity="${max_wheel_velocity}" />
102102
</joint>
103103
<xacro:wheel_transmissions prefix="front_left_motor" />
104104

@@ -130,7 +130,7 @@
130130
<child link="back_right_wheel" />
131131
<axis xyz="0 -1 0" />
132132
<dynamics damping="1.0" />
133-
<limit effort="${max_effort}" velocity="${max_velocity}" />
133+
<limit effort="${max_effort}" velocity="${max_wheel_velocity}" />
134134
</joint>
135135
<xacro:wheel_transmissions prefix="back_right_motor" />
136136

@@ -162,7 +162,7 @@
162162
<child link="back_left_wheel" />
163163
<axis xyz="0 -1 0" />
164164
<dynamics damping="1.0" />
165-
<limit effort="${max_effort}" velocity="${max_velocity}" />
165+
<limit effort="${max_effort}" velocity="${max_wheel_velocity}" />
166166
</joint>
167167
<xacro:wheel_transmissions prefix="back_left_motor" />
168168

ipa_ros2_control/src/curt_mini_hardware_interface.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ CallbackReturn CurtMiniHardwareInterface::on_init(const hardware_interface::Hard
2222

2323
RCLCPP_INFO(nh_->get_logger(), "Name: %s", info_.name.c_str());
2424

25-
RCLCPP_INFO(nh_->get_logger(), "Number of Joints %u", info_.joints.size());
25+
RCLCPP_INFO(nh_->get_logger(), "Number of Joints %zu", info_.joints.size());
2626

2727
hw_states_position_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN());
2828
hw_states_velocity_.resize(info_.joints.size(), std::numeric_limits<double>::quiet_NaN());

0 commit comments

Comments
 (0)