This project provides a ros2_control
SystemInterface
for mjbots pi3hat.
Huge thanks to Gabrael Levine and his version of pi3hat_hardware_interface
for inspiration and making this work much more easier!
- ☑️ Different kinds of controllers (for making wrapper for your kind of controller check below)
- ☑️ Transmission interface (
SimpleTransmission
,FourBarLinkageTransmission
andDifferentialTransmission
) - ☑️ Simple transformation for IMU (
z
axis now points "up") - ☑️ 3 joint command interfaces:
- position [
radians]
- velocity [
radians/s
] - effort [
Nm
]
- position [
- ☑️ 4 joint state interfaces:
- position [
radians/s
] - velocity [
radians/s
] - effort [
Nm
] - temperature [
Celcius
]
- position [
- ☑️ 10 IMU state interfaces (ready to use for IMU Sensor Broadcaster):
- orientation (
x
,y
,z
andw
) - angular velocity (
x
,y
,z
) [radians/s
] - linear acceleration (
x
,y
,z
) [m/s^2
]
- orientation (
⚠️ IMPORTANT: User don't have to set up every command or state interface in xml
file, but remeber to set up your controller accordingly e.g. in order to control velocity in moteus
controller, u need to set up kp
coefficient to 0.0.
- Raspberry Pi 4 (more RAM the better)
- pi3hat
- ros2_control
- ros2_controllers
- pi3hat (already in project)
- moteus (already in project)
- Clone repo to your workspace:
git clone https://github.com/BartlomiejK2/pi3hat_hardware_interface.git
- Create link to library
bcm_host
:
sudo ln /usr/lib/aarch64-linux-gnu/libbcm_host.so /usr/lib/libbcm_host.so.0
- Install dependencies:
rosdep install --ignore-src --from-paths . -y -r
- Build (only works on Raspberry Pi):
colcon build --packages-select pi3hat_hardware_interface
<ros2_control name="pi3hat_hardware_interface" type="system">
<hardware>
<plugin>pi3hat_hardware_interface/Pi3HatHardwareInterface</plugin>
<param name="imu_mounting_deg.yaw">0</param>
<param name="imu_mounting_deg.pitch">0</param>
<param name="imu_mounting_deg.roll">0</param>
<param name="imu_sampling_rate">1000</param>
<param name="can_1_fdcan_frame">true</param>
<param name="can_1_automatic_retransmission">true</param>
<param name="can_1_bitrate_switch">true</param>
<param name="can_2_fdcan_frame">true</param>
<param name="can_2_automatic_retransmission">true</param>
<param name="can_2_bitrate_switch">true</param>
<param name="can_3_fdcan_frame">true</param>
<param name="can_3_automatic_retransmission">true</param>
<param name="can_3_bitrate_switch">true</param>
<param name="can_4_fdcan_frame">true</param>
<param name="can_4_automatic_retransmission">true</param>
<param name="can_4_bitrate_switch">true</param>
<param name="can_5_fdcan_frame">true</param>
<param name="can_5_automatic_retransmission">true</param>
<param name="can_5_bitrate_switch">true</param>
</hardware>
...
</ros2_control>
imu_mounting_deg.*
- IMU RPY mouting relative to fixed link [degrees
]
imu_sampling_rate
- IMU rate for attitude sampling (400 or 1000 are the best) [Hz
]
can_X_fdcan_frame
- Using FDCAN frame in X CAN bus [bool
]
can_X_automatic_retransmission
- Using automatic retransmission in X CAN bus [bool
]
can_X_bitrate_switch
- Using bitrate switch in X CAN bus [bool
]
...
<joint name="joint_1">
<param name="controller_type">moteus</param>
<param name="controller_can_bus">1</param>
<param name="controller_can_id">1</param>
<param name="motor_direction">1</param>
<param name="motor_position_offset">0.0</param>
<param name="motor_position_max">500.0</param>
<param name="motor_position_min">-500.0</param>
<param name="motor_velocity_max">10.0</param>
<param name="motor_torque_max">1.0</param>
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name = "position"/>
<state_interface name = "velocity"/>
<state_interface name = "effort"/>
<state_interface name = "temperature"/>
</joint>
...
controller_type
- Type of controller (now only moteus supported)
controller_can_bus
- CAN bus which controller is connected
controller_id
- Controller Id
motor_direction
- Motor direction (1 or -1)
motor_position_offset
- Motor position offset, will be added to commanded position before sending to controller [radians
]
motor_position_max/min
- Motor max/min position [radians
]
motor_velocity_max
- Motor maximal velocity [radians
]
motor_torque_max
- Motor maximal torque [Nm
]
- Go to
test/controllers
- Choose controller type directory
- Compile tests:
bash "type"_wrapper_tests_compile.sh
- Run tests:
sudo simple_wrapper_"type"_test
sudo single_wrapper_"type"_test
sudo double_wrapper_"type"_test
- Go to
test/urdf
- Choose urdfs with your controller type
- Edit urdf with your options
- Build project
- Source project
- Run:
ros2 launch pi3hat_hardware_interface test_"amount"_"type".launch.py
Check out Gabrael Levine Troubleshooting.
- Check
include/controllers/wrappers/MoteusWrapper.hpp
andsrc/controllers/wrappers/MoteusWrapper.cpp
. - Add third-party library to
include/3rd_libs/
. - Add third-party party library to
CMakelist.txt
asadd_library
(likepi3hat
andmoteus
). - Create
"Type"Wrapper.hpp
file for your controller wrapper ininclude/controllers/wrappers
. - Add include path to
"Type"Wrapper.hpp
file ininclude/controllers/Controllers.hpp
. - Create
"Type"Wrapper.cpp
file with implementation insrc/controllers/wrappers
. - Add your
"Type"Wrapper.cpp
file to librarycontrollers
inCMakelist.txt
. - Go to
src/controllers/ControllerBridge.cpp
. - Add
else if
with your controller type asstd::string
with construction of your wrapper inside. - Add comments to your code (check other source and header files).
- Add wrapper tests for wrapper in
test/controllers/"type"
(check tests formoteus
). - Add tests for pi3hat with your wrapper in
test/urdf
andtest/bringup/launch
(check tests formoteus
). - Run all tests.
- Create pull request with your code. Write description of your changes.
- Change code.
- Run all tests.
- If all passed, create pull request with your code. Write description of your changes.