Skip to content

Commit

Permalink
cleanup
Browse files Browse the repository at this point in the history
  • Loading branch information
ARK3r committed Jan 29, 2024
1 parent ec2759d commit f973b38
Show file tree
Hide file tree
Showing 6 changed files with 30 additions and 34 deletions.
2 changes: 1 addition & 1 deletion doc/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ Example 10: "GPIO interfaces"
Industrial robot with GPIO interfaces

Example 11: "CarlikeBot"
*CarlikeBot* with an Ackermann steering controller
*CarlikeBot* with a bicycle steering controller

Example 12: "Controller chaining"
The example shows a simple chainable controller and its integration to form a controller chain to control the joints of *RRBot*.
Expand Down
4 changes: 2 additions & 2 deletions example_11/README.md
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
# ros2_control_demo_example_11

*CarlikeBot*, or ''Carlike Mobile Robot'', is a simple mobile base with [ackermann drive](https://en.wikipedia.org/wiki/Ackermann_steering_geometry).
The robot has two wheels in the front that steer the robot and two wheels in the back that power the robot forward and backwards.
*CarlikeBot*, or ''Carlike Mobile Robot'', is a simple mobile base with bicycle drive.
The robot has two wheels in the front that steer the robot and two wheels in the back that power the robot forward and backwards. However, since each pair of wheels (steering and traction) are controlled by one interface, a bicycle steering model is used.

Find the documentation in [doc/userdoc.rst](doc/userdoc.rst) or on [control.ros.org](https://control.ros.org/master/doc/ros2_control_demos/example_11/doc/userdoc.html).
2 changes: 1 addition & 1 deletion example_11/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -128,4 +128,4 @@ Controllers from this demo
--------------------------

* ``Joint State Broadcaster`` (`ros2_controllers repository <https://github.com/ros-controls/ros2_controllers/tree/{REPOS_FILE_BRANCH}/joint_state_broadcaster>`__): `doc <https://control.ros.org/{REPOS_FILE_BRANCH}/doc/ros2_controllers/joint_state_broadcaster/doc/userdoc.html>`__
* ``Bicycle Steering Controller`` (`ros2_controllers repository <https://github.com/ros-controls/ros2_controllers/tree/{REPOS_FILE_BRANCH}/bicycle_steering_controller>`__): `doc <https://control.ros.org/{REPOS_FILE_BRANCH}/doc/ros2_controllers/ackermann_steering_controller/doc/userdoc.html>`__
* ``Bicycle Steering Controller`` (`ros2_controllers repository <https://github.com/ros-controls/ros2_controllers/tree/{REPOS_FILE_BRANCH}/bicycle_steering_controller>`__): `doc <https://control.ros.org/{REPOS_FILE_BRANCH}/doc/ros2_controllers/bicycle_steering_controller/doc/userdoc.html>`__
53 changes: 24 additions & 29 deletions example_11/hardware/carlikebot_system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -281,18 +281,21 @@ hardware_interface::return_type CarlikeBotSystemHardware::read(
const rclcpp::Time & /*time*/, const rclcpp::Duration & period)
{
// BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
for (auto & joint : hw_interfaces_)
{
if (joint.first == "steering")
{
joint.second.state.position = joint.second.command.position;
}
else if (joint.first == "traction")
{
joint.second.state.velocity = joint.second.command.velocity;
joint.second.state.position += joint.second.state.velocity * period.seconds();
}
}

hw_interfaces_["steering"].state.position = hw_interfaces_["steering"].command.position;

hw_interfaces_["traction"].state.velocity = hw_interfaces_["traction"].command.velocity;
hw_interfaces_["traction"].state.position +=
hw_interfaces_["traction"].state.velocity * period.seconds();

RCLCPP_INFO(
rclcpp::get_logger("CarlikeBotSystemHardware"), "Got position state: %.2f for joint '%s'.",
hw_interfaces_["steering"].command.position, hw_interfaces_["steering"].joint_name.c_str());

RCLCPP_INFO(
rclcpp::get_logger("CarlikeBotSystemHardware"), "Got velocity state: %.2f for joint '%s'.",
hw_interfaces_["traction"].command.velocity, hw_interfaces_["traction"].joint_name.c_str());

// END: This part here is for exemplary purposes - Please do not copy to your production code

return hardware_interface::return_type::OK;
Expand All @@ -302,23 +305,15 @@ hardware_interface::return_type ros2_control_demo_example_11 ::CarlikeBotSystemH
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
{
// BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
for (auto & joint : hw_interfaces_)
{
if (joint.first == "steering")
{
RCLCPP_INFO(
rclcpp::get_logger("CarlikeBotSystemHardware"),
"Got position command: %.2f for joint '%s'.", joint.second.command.position,
joint.second.joint_name.c_str());
}
else if (joint.first == "traction")
{
RCLCPP_INFO(
rclcpp::get_logger("CarlikeBotSystemHardware"),
"Got velocity command: %.2f for joint '%s'.", joint.second.command.velocity,
joint.second.joint_name.c_str());
}
}

RCLCPP_INFO(
rclcpp::get_logger("CarlikeBotSystemHardware"), "Got position command: %.2f for joint '%s'.",
hw_interfaces_["steering"].command.position, hw_interfaces_["steering"].joint_name.c_str());

RCLCPP_INFO(
rclcpp::get_logger("CarlikeBotSystemHardware"), "Got velocity command: %.2f for joint '%s'.",
hw_interfaces_["traction"].command.velocity, hw_interfaces_["traction"].joint_name.c_str());

// END: This part here is for exemplary purposes - Please do not copy to your production code

return hardware_interface::return_type::OK;
Expand Down
1 change: 1 addition & 0 deletions example_11/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>ros2_controllers_test_nodes</exec_depend>
<exec_depend>ros2_control_demo_description</exec_depend>
<exec_depend>topic_tools</exec_depend>
<exec_depend>ros2controlcli</exec_depend>
<exec_depend>ros2launch</exec_depend>
<exec_depend>rviz2</exec_depend>
Expand Down
2 changes: 1 addition & 1 deletion example_11/ros2_control_demo_example_11.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
type="ros2_control_demo_example_11::CarlikeBotSystemHardware"
base_class_type="hardware_interface::SystemInterface">
<description>
The ros2_control CarlikeBot example using a system hardware interface-type. It uses velocity command and state interface for the drive motor and position command and state interface for the steering. The example is the starting point to implement a hardware interface for ackermann and bicycle drive robots.
The ros2_control CarlikeBot example using a system hardware interface-type. It uses velocity and position command and state interface for the drive motor and position command and state interface for the steering. The example is the starting point to implement a hardware interface for ackermann and bicycle drive robots.
</description>
</class>
</library>

0 comments on commit f973b38

Please sign in to comment.