Ignition with ros2_control internals
continue to Let's try Ignition Fortress, just wanted to comprehend the architecture and design how it works
for Ignition with ros2_control.
Build and Run ign_ros2_control
-
Install
ros:galactic
on ubuntu:20.04, see Installing ROS 2 via Debian Packages -
Build ign_ros2_control
# source ros:galactic env
source /opt/ros/galactic/setup.bash
# build sample colcon workspace
export IGNITION_VERSION=fortress
mkdir -p ~/ros_ign/src
cd ~/ros_ign/src
git clone https://github.com/ignitionrobotics/ign_ros2_control
rosdep install -r --from-paths . --ignore-src --rosdistro $ROS_DISTRO -y
cd ~/ros2_ign
colcon build
- Run ign_ros2_control
ros2 launch ign_ros2_control_demos cart_example_velocity.launch.py
...
ros2 run ign_ros2_control_demos example_velocity
...
Architecture / Design
this is ros2_control framework overview, as we can see user needs to develop Controller
, Interface
and Plugin
such as Sensor, System and Actuator to integrate with ros2_control.
Implementation Detail
from ros2_control perspective, Ignition is one of System
hardware object. IgnitionSystem
possesses IgnitionSystemInterface
inherited from hardware_interface::SystemInterface
.
in other words, Ignition is just a hardware to control and plugged in to ros2_control.
we can refer to the implementation as below.
then sending velocity messages via /velocity_controller/commands
topic to /velocity_controller
to write the data IgnitionSystem
joint slider_to_cart
.
<ros2_control name="IgnitionSystem" type="system">
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</hardware>
<joint name="slider_to_cart">
<command_interface name="velocity">
<param name="min">-15</param>
<param name="max">15</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
IgnitionROS2ControlPlugin
is one of the Ignition Gazebo System
plugin library.
It provides callback methods such as Configure
, PreUpdate
and PostUpdate
.
-
Configure
will be called during initialization. in this plugin, it will read URDF from parameter server and instantiate ros2_controlControllerManager
with parameters. -
PreUpdate
will be called before modify state before physics runs. It callscontroller_manager_->write
that leads toIgnitionSystem::write
to updateignition::gazebo::components
. -
PreUpdate
is mapped toIgnitionSystem::read
.