ROS - HowardWhile/2023_note GitHub Wiki
r6bot
這是ros2 controller demo的6軸機器人
ros2 launch ros2_control_demo_example_7 view_r6bot.launch.py
joint並沒有參考特定的DH參數排列
UR
這是大家都愛用的**Universal_Robots_ROS2_Description**
sudo apt install ros-humble-ur-description
ros2 launch ur_description view_ur.launch.py ur_type:=ur5
joint參考M-DH排列
FANAC
fanuc_description感覺有點粗糙我要再找找比較有公信力的urdf來源
KUKA
可以前往ros2的入口網站 ROS Index 使用關鍵字description
搜尋。舉例來說想要找FANUC
機器人的描述檔可以透過關鍵字。
+description +FANUC
ros社群約定使用description作為機器人的描述檔package的名稱
https://github.com/HowardWhile/urdf_demo
http://wiki.ros.org/urdf/XML/link
關於模型質量的各種參數<origin>
<mass>
<inertia>
要如何取得呢?
我這邊透過solidwork來評估。
點選評估->物質特性
ROS系統採用KMS製所以記得到這邊設定
將質量填入<mass>
將質量中心填入<origin>
將慣性矩填入<inertia>
http://wiki.ros.org/urdf/XML/link
inertia
This link's moments of inertia...https://zh.wikipedia.org/zh-tw/%E8%BD%89%E5%8B%95%E6%85%A3%E9%87%8F
轉動慣量 (Moment of inertia) 在古典力學中,轉動慣量又稱慣性矩,通常以I表示...
sudo apt install ros-humble-ur-description
ros2 launch ur_description view_ur.launch.py ur_type:=ur5e
要建立ec0902的ethercat控制器可以這樣子做。
透過RosTeamWs的工具初始化名為ws_ethercat
的工作空間
setup-ros-workspace ~/workspace/ws_ethercat humble
參考ethercat_driver_ros2安裝 https://icube-robotics.github.io/ethercat_driver_ros2/quickstart/installation.html
要注意的是這邊用到的目錄是~/workspace/ws_ethercat/src
為了在ROS 2控制架構中控制 EtherCAT 設備,需要實現相關的 controller
和 hardware
。在這個過程中,必須創建描述 (description
)、啟動 (bringup
),以及控制 (controller
) 相關的元件。在 hardware
方面,可以使用 ethercat_driver_ros2
中提供的典型 ethercat_generic_slave。因此,需要建立以下三個 package
以實現所需的控制功能:
-
描述
(description)package
-
啟動
(bringup)package
-
控制
(controller)package
這邊使用
RosTeamWs
來初始化模板。所以要先參考RosTeamWs配置環境
_ws_ethercat
rosds
mkdir ec0902
cd ec0902
create-new-package ec0902_description "delta R2-EC0902 - description"
create-new-package ec0902_bringup "delta R2-EC0902 - bringup"
create-new-package ec0902_controller "delta R2-EC0902 - controller"
關於配置選擇
What type of package you want to create?
1) standard
2) metapackage
3) subpackage
#? 1
Who will maintain the package you want to create? Please provide the info:
1) user input
2) global git: HowardWhile <[email protected]>
#? 1
How do you want to licence your package?
#? 10
Please choose your package build type:
1) ament_cmake
2) ament_python
3) cmake
#? 1
Do you want to setup/update repository with the new package configuration? [yes no]
#? no
setup-robot-description <my_cool_robot_name>
_ws_ethercat
rosd
cd src/ec0902/ec0902_description/
setup-robot-description r2_ec0902
cb ec0902_description
ros2_control_setup-controller-package <my_controller_file_name>
_ws_ethercat
rosd
cd src/ec0902/ec0902_controller/
ros2_control_setup-controller-package ec0902_controller
關於配置選擇
Which license-header do you want to use? [1]
(0) None
(1) Apache-2.0
(2) Proprietary
#? 1
Insert your company or personal name (copyright):
#? howard
Is package already configured (is in there a working controller already)? (yes/no) [no]
#? no
Do you want to setup a 'normal' or 'chainable' controller? [1]
(1) normal (single-level control)
(2) chainable
#? 1
setup-robot-bringup <my_cool_robot_name> <my_cool_robot_description_package_name>
_ws_ethercat
rosd
cd src/ec0902/ec0902_bringup/
setup-robot-bringup r2_ec0902 ec0902_description
由於目標是測試EtherCAT,因此可以刪除與機器人模型3D相關的檔案以及觀看3D相關的檔案,這些對目前的測試不需要。
以下資料夾可以刪除
- launch
- meshes
- rviz
同時需要編輯CMakeLists.txt
將這些資料夾從install階段移除
install(
#DIRECTORY config launch meshes rviz urdf
DIRECTORY config urdf #修改
DESTINATION share/${PROJECT_NAME}
)
以下檔案可以刪除
./ec0902_description/urdf/r2_ec0902/r2_ec0902_macro.xacro
./ec0902_description/urdf/common.xacro
模板中URDF描述檔巨集的進入位置在 ./ec0902_description/urdf/r2_ec0902.urdf.xacro
。打開後進行如下編輯:
只保留下以下這一行:
<xacro:include filename="$(find ec0902_description)/urdf/r2_ec0902/r2_ec0902_macro.ros2_control.xacro"/>
其餘部分請先移除。編輯後的文件如下所示:
<?xml version="1.0" encoding="UTF-8"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="r2_ec0902">
<xacro:include filename="$(find ec0902_description)/urdf/r2_ec0902/r2_ec0902_macro.ros2_control.xacro"/>
</robot>
ref https://icube-robotics.github.io/ethercat_driver_ros2/user_guide/config_generic_slave.html
模板產生的檔案中,ros2_control.xacro (./ec0902_description/urdf/r2_ec0902/r2_ec0902_macro.ros2_control.xacro
) 檔案,可以定義ros2_control要載入的插件,並配置相關的interface。這裡按照ethercat_driver_ros2建議載入 ethercat_driver/EthercatDriver
和 ethercat_generic_plugins/GenericEcSlave
,並進行相應的設定。編輯後的文件如下所示:
<?xml version="1.0" encoding="UTF-8"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<ros2_control name="r2_ec0902" type="system">
<hardware>
<plugin>ethercat_driver/EthercatDriver</plugin>
<param name="master_id">0</param>
<param name="control_frequency">100</param>
</hardware>
<gpio name="gpio_0">
<command_interface name="p1/output"/>
<command_interface name="p2/output"/>
<command_interface name="p3/output"/>
<command_interface name="p4/output"/>
<state_interface name="p1/input"/>
<state_interface name="p2/input"/>
<state_interface name="p3/input"/>
<state_interface name="p4/input"/>
<ec_module name="R2_EC0902">
<plugin>ethercat_generic_plugins/GenericEcSlave</plugin>
<param name="alias">0</param>
<param name="position">0</param>
<param name="slave_config">$(find ec0902_description)/config/EC0902_slave_config.yaml</param>
</ec_module>
</gpio>
</ros2_control>
</robot>
ref https://icube-robotics.github.io/ethercat_driver_ros2/user_guide/config_generic_slave.html
名為 EC0902_slave_config.yaml
的配置檔放在 ./ec0902_description/config/EC0902_slave_config.yaml
的路徑下,以便在 ros2_control.xacro
檔案中的 slave_config
變數中引用。這個檔案將用於定義EtherCAT slave的SDO配置、PDO映射、Sync Manager配置等等設定。該如何配置要參考DELTA EC0902的IO模組的說明文件,同時也要參考ethercat_driver_ros2說明文件。配置完成的檔案內容如下︰
vendor_id: 0x000001DD
product_id: 0x00000902
assign_activate: 0x0300 # DC Synch register
# -------------------------------------------------------------------------
# sdo data to be transferred at drive startup
# -------------------------------------------------------------------------
sdo:
# DO Setting Value
- {index: 0x6200, sub_index: 1, type: uint8, value: 255}
- {index: 0x6200, sub_index: 2, type: uint8, value: 255}
- {index: 0x6200, sub_index: 3, type: uint8, value: 255}
- {index: 0x6200, sub_index: 4, type: uint8, value: 255}
# Active DO Enable
- {index: 0x2001, sub_index: 1, type: uint8, value: 255}
- {index: 0x2001, sub_index: 2, type: uint8, value: 255}
- {index: 0x2001, sub_index: 3, type: uint8, value: 255}
- {index: 0x2001, sub_index: 4, type: uint8, value: 255}
# DO Error Mode Enable
- {index: 0x6206, sub_index: 1, type: uint8, value: 0}
- {index: 0x6206, sub_index: 2, type: uint8, value: 0}
- {index: 0x6206, sub_index: 3, type: uint8, value: 0}
- {index: 0x6206, sub_index: 4, type: uint8, value: 0}
# DO Error Mode Setting Value
- {index: 0x6207, sub_index: 1, type: uint8, value: 0}
- {index: 0x6207, sub_index: 2, type: uint8, value: 0}
- {index: 0x6207, sub_index: 3, type: uint8, value: 0}
- {index: 0x6207, sub_index: 4, type: uint8, value: 0}
# -------------------------------------------------------------------------
# Transmit PDO mapping configuration.
# -------------------------------------------------------------------------
tpdo: # TxPDO
- index: 0x1a00
channels:
# 0x6000:01, r-r-r-, uint8, 8 bit, "Read Port0 Input CH0~7 8Bit"
# 0x6000:02, r-r-r-, uint8, 8 bit, "Read Port0 Input CH8~15 8Bit"
# 0x6000:03, r-r-r-, uint8, 8 bit, "Read Port1 Input CH0~7 8Bit"
# 0x6000:04, r-r-r-, uint8, 8 bit, "Read Port1 Input CH8~15 8Bit"
- {index: 0x6000, sub_index: 1, type: uint8, state_interface: "p1/input"}
- {index: 0x6000, sub_index: 2, type: uint8, state_interface: "p2/input"}
- {index: 0x6000, sub_index: 3, type: uint8, state_interface: "p3/input"}
- {index: 0x6000, sub_index: 4, type: uint8, state_interface: "p4/input"}
# -------------------------------------------------------------------------
# Receive PDO mapping configuration.
# -------------------------------------------------------------------------
rpdo: # RxPDO
- index: 0x1600
channels:
# 0x6200:01, rwrwrw, uint8, 8 bit, "Port2 DO CH0~7 Setting Value"
# 0x6200:02, rwrwrw, uint8, 8 bit, "Port2 DO CH8~15 Setting Value"
# 0x6200:03, rwrwrw, uint8, 8 bit, "Port3 DO CH0~7 Setting Value"
# 0x6200:04, rwrwrw, uint8, 8 bit, "Port3 DO CH8~15 Setting Value"
- {index: 0x6200, sub_index: 1, type: uint8, command_interface: "p1/output"}
- {index: 0x6200, sub_index: 2, type: uint8, command_interface: "p2/output"}
- {index: 0x6200, sub_index: 3, type: uint8, command_interface: "p3/output"}
- {index: 0x6200, sub_index: 4, type: uint8, command_interface: "p4/output"}
# -------------------------------------------------------------------------
# Sync Manager configuration.
# -------------------------------------------------------------------------
sm: # Sync Manager
- {index: 0, type: output, pdo: ~, watchdog: disable}
- {index: 1, type: input, pdo: ~, watchdog: disable}
- {index: 2, type: output, pdo: rpdo, watchdog: disable}
- {index: 3, type: input, pdo: tpdo, watchdog: disable}
使用bringup來launch看看。
ros2 launch ec0902_bringup r2_ec0902.launch.py
稍等約10秒鐘就可以看到ec0902的Run指示燈變成op模式(恆亮)。因為還沒有修改bringup的launch檔,會有controller_manager發出的錯誤訊息可以先忽略。
接下來透過指令顯示hardware_interfaces
ros2 control list_hardware_interfaces
command interfaces
gpio_0/p1/output [available] [unclaimed]
gpio_0/p2/output [available] [unclaimed]
gpio_0/p3/output [available] [unclaimed]
gpio_0/p4/output [available] [unclaimed]
state interfaces
gpio_0/p1/input
gpio_0/p2/input
gpio_0/p3/input
gpio_0/p4/input
就能看到ros2_control.xacro中定義的控制器接口。因為還沒有維護controller所以command interfaces會顯示 [unclaimed]
主要目標是修改 ec0902_controller.cpp
檔案。ControllerInterface
有定義7個事件接口:on_init
, command_interface_configuration
, state_interface_configuration
, on_configure
, on_activate
, on_deactivate
, update
,首先聚焦在2個事件接口,即:
command_interface_configuration
state_interface_configuration
請參考 ./ec0902_description/urdf/r2_ec0902/r2_ec0902_macro.ros2_control.xacro
中 <command_interface>
和 <state_interface>
標籤的描述,我們將按照這些描述來修改ec0902_controller.cpp
的事件接口,變動後的內容如下:
controller_interface::InterfaceConfiguration Ec0902Controller::command_interface_configuration() const
{
controller_interface::InterfaceConfiguration command_interfaces_config;
command_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL;
command_interfaces_config.names.push_back("gpio_0/p1/output");
command_interfaces_config.names.push_back("gpio_0/p2/output");
command_interfaces_config.names.push_back("gpio_0/p3/output");
command_interfaces_config.names.push_back("gpio_0/p4/output");
return command_interfaces_config;
}
controller_interface::InterfaceConfiguration Ec0902Controller::state_interface_configuration() const
{
controller_interface::InterfaceConfiguration state_interfaces_config;
state_interfaces_config.type = controller_interface::interface_configuration_type::INDIVIDUAL;
state_interfaces_config.names.push_back("gpio_0/p1/input");
state_interfaces_config.names.push_back("gpio_0/p2/input");
state_interfaces_config.names.push_back("gpio_0/p3/input");
state_interfaces_config.names.push_back("gpio_0/p4/input");
return state_interfaces_config;
}
gpio_0最好要參數化,單台設備沒有影響,但這種寫法在多台設備會有interface名稱重複的問題
剩餘的5個事件接口
on_init
on_configure
on_activate
on_deactivate
updated
可以將它們的內容清空以便進行編譯,我將模板程式修改如下︰
controller_interface::CallbackReturn Ec0902Controller::on_init()
{
RCLCPP_INFO(get_node()->get_logger(), "on_init()");
control_mode_.initRT(control_mode_type::FAST);
try
{
param_listener_ = std::make_shared<ec0902_controller::ParamListener>(get_node());
}
catch (const std::exception &e)
{
fprintf(stderr, "Exception thrown during controller's init with message: %s \n", e.what());
return controller_interface::CallbackReturn::ERROR;
}
return controller_interface::CallbackReturn::SUCCESS;
}
//....
//....
//....
controller_interface::CallbackReturn Ec0902Controller::on_configure(const rclcpp_lifecycle::State & /*previous_state*/)
{
RCLCPP_INFO(get_node()->get_logger(), "on_configure()");
params_ = param_listener_->get_params();
return controller_interface::CallbackReturn::SUCCESS;
}
controller_interface::CallbackReturn Ec0902Controller::on_activate(const rclcpp_lifecycle::State & /*previous_state*/)
{
RCLCPP_INFO(get_node()->get_logger(), "on_activate()");
return controller_interface::CallbackReturn::SUCCESS;
}
controller_interface::CallbackReturn Ec0902Controller::on_deactivate(const rclcpp_lifecycle::State & /*previous_state*/)
{
RCLCPP_INFO(get_node()->get_logger(), "on_deactivate()");
return controller_interface::CallbackReturn::SUCCESS;
}
controller_interface::return_type Ec0902Controller::update(const rclcpp::Time & time, const rclcpp::Duration & /*period*/)
{
RCLCPP_INFO(get_node()->get_logger(), "update()");
return controller_interface::return_type::OK;
}
模板./ec0902_controller/CMakeLists.txt
之中BUILD_TESTING
還原成預設內容,修改如下︰
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# comment the line when a copyright and license is added to all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# comment the line when this package is in a git repo and when
# a copyright and license is added to all source files
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
controller參數定義在這個路徑./ec0902_controller/src/ec0902_controller.yaml
,模板定義的參數不一定要用我先隨意使用教學的範例替代。修改如下。
ec0902_controller:
background:
r: {
type: int,
default_value: 0,
description: "Red color value for the background, 8-bit",
validation: {
bounds<>: [0, 255]
}
}
g: {
type: int,
default_value: 0,
description: "Green color value for the background, 8-bit",
validation: {
bounds<>: [0, 255]
}
}
b: {
type: int,
default_value: 0,
description: "Blue color value for the background, 8-bit",
validation: {
bounds<>: [0, 255]
}
}
參數的產生用到
generate_parameter_library
,產生參數的過程,可以參考https://github.com/PickNikRobotics/generate_parameter_library的教學,這邊就不多敘述
首先,請維護 ./ec0902_bringup/config/r2_ec0902_controllers.yaml
中的參數檔,並新增一個 ec0902_controller
,並指定其型態為 ec0902_controller/Ec0902Controller
,如下所示:
controller_manager:
ros__parameters:
update_rate: 100 # Hz
ec0902_controller:
type: ec0902_controller/Ec0902Controller
# .....
請確保型態的名稱與 ./ec0902_controller/ec0902_controller.xml
中 <class name=
標籤中描述的 ec0902_controller/Ec0902Controller
相對應。
接下來,使用 bringup
來啟動:
ros2 launch ec0902_bringup r2_ec0902.launch.py
透過指令列出controller:
ros2 control list_controllers
您將會看到目前只有模板預載的控制器:
joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster] active
forward_position_controller[forward_command_controller/ForwardCommandController] inactive
此時,您可以透過以下指令載入剛剛完成的 ec0902_controller
:
ros2 control load_controller ec0902_controller
再次透過指令列出controller:
ros2 control list_controllers
您將會看到 ec0902_controller
已經被載入,但處於 unconfigured
狀態:
joint_state_broadcaster[joint_state_broadcaster/JointStateBroadcaster] active
forward_position_controller[forward_command_controller/ForwardCommandController] inactive
ec0902_controller [ec0902_controller/Ec0902Controller] unconfigured
接續測試1
可以透過指令顯示description
package中定義的hardware_interfaces
ros2 control list_hardware_interfaces
command interfaces
gpio_0/p1/output [available] [unclaimed]
gpio_0/p2/output [available] [unclaimed]
gpio_0/p3/output [available] [unclaimed]
gpio_0/p4/output [available] [unclaimed]
state interfaces
gpio_0/p1/input
gpio_0/p2/input
gpio_0/p3/input
gpio_0/p4/input
可以看到command interface目前是處於**[unclaimed]**狀態
透過指令切換controller狀態
ros2 control set_controller_state ec0902_controller inactive
ros2 control set_controller_state ec0902_controller active
再次透過指令顯示hardware_interfaces
ros2 control list_hardware_interfaces
command interfaces
gpio_0/p1/output [available] [claimed]
gpio_0/p2/output [available] [claimed]
gpio_0/p3/output [available] [claimed]
gpio_0/p4/output [available] [claimed]
state interfaces
gpio_0/p1/input
gpio_0/p2/input
gpio_0/p3/input
gpio_0/p4/input
可以看到command interface已經切換成**[claimed]**狀態
且透過ros2 launch ec0902_bringup r2_ec0902.launch.py
的 ros2_control正在不斷執行update()。
[ros2_control_node-1] [INFO] [1694765859.679332623] [controller_manager]: Loading controller 'ec0902_controller'
[ros2_control_node-1] [INFO] [1694765859.685629874] [ec0902_controller]: on_init()
[ros2_control_node-1] [INFO] [1694765994.661626392] [controller_manager]: Configuring controller 'ec0902_controller'
[ros2_control_node-1] [INFO] [1694765994.661717183] [ec0902_controller]: on_configure()
[ros2_control_node-1] [INFO] [1694766006.776350344] [ec0902_controller]: command_interface_configuration()
[ros2_control_node-1] [INFO] [1694766006.776436644] [ec0902_controller]: state_interface_configuration()
[ros2_control_node-1] [INFO] [1694766006.779393226] [ec0902_controller]: command_interface_configuration()
[ros2_control_node-1] [INFO] [1694766006.779452984] [ec0902_controller]: command_interface_configuration()
[ros2_control_node-1] [INFO] [1694766006.779707682] [ec0902_controller]: command_interface_configuration()
[ros2_control_node-1] [INFO] [1694766006.779738733] [ec0902_controller]: state_interface_configuration()
[ros2_control_node-1] [INFO] [1694766006.779762600] [ec0902_controller]: on_activate()
[ros2_control_node-1] [INFO] [1694766006.779852106] [ec0902_controller]: command_interface_configuration()
[ros2_control_node-1] [INFO] [1694766006.789720489] [ec0902_controller]: update()
[ros2_control_node-1] [INFO] [1694766006.799726194] [ec0902_controller]: update()
[ros2_control_node-1] [INFO] [1694766006.809727896] [ec0902_controller]: update()
[ros2_control_node-1] [INFO] [1694766006.819728645] [ec0902_controller]: update()
# .......
在ros2_control架構中,
controller
以插件的形式運作,因此在程式中不會有main()
函數,取而代之的是提供了許多controller_interface
的函數接口,供ros2_controll調用。有關ROS插件和ros2_control接口的相關資訊和教程可以參考以下連結:
- ros2_control接口資訊 這邊也有提到建議使用RosTeamWS的腳本來初始化控制器
- ROS2 插件教學
先移除模板中不需要的範例程式。
以下檔案可以刪除
./ec0902_bringup/config/test_goal_publishers_config.yaml
./ec0902_bringup/launch/test_forward_position_controller.launch.py
./ec0902_bringup/launch/test_joint_trajectory_controller.launch.py
bringup的launch檔位置是./ec0902_bringup/launch/r2_ec0902.launch.py
是專案約定的主要launch檔,主要運行controller_manager並且使用spawner載入ec0902_controller。
./ec0902_bringup/launch/r2_ec0902.launch.py
修改後如下
from launch import LaunchDescription
from launch.substitutions import Command, FindExecutable, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
def generate_launch_description():
# ----------------------------------------------------------------
# controller_manager initial
# ----------------------------------------------------------------
# Get URDF via xacro
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution(
[
FindPackageShare("ec0902_description"),
"urdf",
"r2_ec0902.urdf.xacro",
]
),
]
)
robot_description = {"robot_description": robot_description_content}
robot_controllers = PathJoinSubstitution(
[FindPackageShare("ec0902_bringup"),
"config",
"r2_ec0902_controllers.yaml"]
)
control_node = Node(
package="controller_manager",
executable="ros2_control_node",
output="both",
parameters=[robot_description, robot_controllers],
)
# ----------------------------------------------------------------
# controller_manager spawner
# ----------------------------------------------------------------
ec0902_controller_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["ec0902_controller", "-c", "/controller_manager"],
)
nodes = [
control_node,
ec0902_controller_spawner
]
return LaunchDescription(nodes)
請維護 ./ec0902_bringup/config/r2_ec0902_controllers.yaml
中的參數檔,並新增一個 ec0902_controller
,並指定其型態為 ec0902_controller/Ec0902Controller
,模板提供的其他參數沒有使用到可以移除。
./ec0902_bringup/config/r2_ec0902_controllers.yaml
編輯後如下
controller_manager:
ros__parameters:
update_rate: 100 # Hz
ec0902_controller:
type: ec0902_controller/Ec0902Controller
ros2 launch ec0902_bringup r2_ec0902.launch.py
顯示controller
可以看到ec0902_controller
啟動後狀態直接處於active
ros2 control list_controllers
ec0902_controller [ec0902_controller/Ec0902Controller] active
顯示硬體接口可以看到command interfaces
已經處於claimed
ros2 control list_hardware_interfaces
command interfaces
gpio_0/p1/output [available] [claimed]
gpio_0/p2/output [available] [claimed]
gpio_0/p3/output [available] [claimed]
gpio_0/p4/output [available] [claimed]
state interfaces
gpio_0/p1/input
gpio_0/p2/input
gpio_0/p3/input
gpio_0/p4/input
EC0902是一個繼電器IO集成的設備,其主要功能是提供IO控制。為了實現這一功能,我們需要為控制器(controller),設計一些topic的接口,以便將IO訊號集成到ROS系統中。
這邊列出存取command interfaces與state interfaces的方法,至於要實做什麼功能就看應用決定。主要修改事件接口update()
controller_interface::return_type Ec0902Controller::update(const rclcpp::Time &time, const rclcpp::Duration & /*period*/)
{
// get data from state interface
std::vector<int8_t> gpio_input;
gpio_input.resize(this->state_interfaces_.size());
for (size_t idx = 0; idx < gpio_input.size(); idx++)
gpio_input[idx] = this->state_interfaces_[idx].get_value();
// set data to command interface
for (size_t idx = 0; idx < command_interfaces_.size(); idx++)
{
this->command_interfaces_[idx].set_value(0x55); //
}
RCLCPP_INFO_THROTTLE(get_node()->get_logger(), *get_node()->get_clock(), 1000,
"update() input: %X %X %X %X",
gpio_input[0],
gpio_input[1],
gpio_input[2],
gpio_input[3]);
return controller_interface::return_type::OK;
}
controller_manager
3個重要的node
ros2 run controller_manager ros2_control_node
ros2 run controller_manager spawner
ros2 run controller_manager unspawner
https://control.ros.org/humble/doc/ros2_control_demos/doc/index.html
https://control.ros.org/humble/doc/ros2_control_demos/doc/index.html#installation
參考Example 1: RRBot
ros2 launch ros2_control_demo_example_1 rrbot.launch.py
切換控制器forward_position_controller
-> joint_trajectory_position_controller
ros2 control load_controller joint_trajectory_position_controller
ros2 control set_controller_state joint_trajectory_position_controller inactive
# ros2 control set_controller_state forward_position_controller inactive
# ros2 control set_controller_state joint_trajectory_position_controller active
ros2 control switch_controllers --activate joint_trajectory_position_controller --deactivate forward_position_controller
測試控制器joint_trajectory_position_controller
ros2 launch ros2_control_demo_example_1 test_joint_trajectory_controller.launch.py
https://rtw.stoglrobotics.de/master/index.html
可以簡化許多指令
Starting >>> rqt_topic
--- stderr: rqt_topic
/home/user/.local/lib/python3.10/site-packages/setuptools/command/install.py:34: SetuptoolsDeprecationWarning: setup.py install is deprecated. Use build and pip and other standards-based tools.
warnings.warn(
---
Finished <<< rqt_topic [1.43s]
SetuptoolsDeprecationWarning: setup.py install is deprecated. Use build and pip and other standards-based tools.
import setuptools
print(setuptools.__version__)
sudo pip install setuptools==58.2.0
我需要roscd ros2的roscd到哪裡去了 https://docs.ros.org/en/humble/Tutorials/Beginner-Client-Libraries/Colcon-Tutorial.html#setup-colcon-cd
現在變成colcon_cd
了
echo "source /usr/share/colcon_cd/function/colcon_cd.sh" >> ~/.bashrc
echo "export _colcon_cd_root=/opt/ros/humble/" >> ~/.bashrc
命令 colcon_cd
允許您快速將 shell 的當前工作目錄更改為包的目錄。例如,colcon_cd <some_ros_package>
會很快將您帶到目錄 ~/ros2_install/src/some_ros_package。
根據您安裝 colcon_cd
的方式和您的工作區所在的位置,上述說明可能會有所不同,請參閱文檔以獲取更多詳細信息。要在 Linux 和 macOS 中撤消此操作,請找到系統的 shell 啟動腳本並刪除附加的 source 和 export 命令。
sudo apt install python3-colcon-common-extensions
# source /usr/share/colcon_argcomplete/hook/colcon-argcomplete.bash
echo "source /usr/share/colcon_argcomplete/hook/colcon-argcomplete.bash" >> ~/.bashrc
https://www.ncnynl.com/archives/202110/4678.html https://moveit.picknik.ai/humble/doc/tutorials/tutorials.html 從原代碼編譯有夠久的
https://zhuanlan.zhihu.com/p/567246503
台大機器人學線上課程 https://www.coursera.org/learn/robotics1/
Warning: Ignoring XDG_SESSION_TYPE=wayland on Gnome. Use QT_QPA_PLATFORM=wayland to run on Wayland anyway.
https://blog.csdn.net/qq_37307332/article/details/123328249
sudo nano /etc/gdm3/custom.conf
#WaylandEnable=false 移除駐節#
重開機
如果想看turtlesim
程序包有多少個執行檔
ros2 pkg executables turtlesim
turtlesim draw_square
turtlesim mimic
turtlesim turtle_teleop_key
turtlesim turtlesim_node
turtlesim
程序包可以這樣安裝
sudo apt install ros-humble-turtlesim
與1代不同launch檔修改之後,必須要執行colcon build 才會生效
CMakeLists.txt
要新增下列代碼才能使用packages路徑來launch
# Install launch files.
install(DIRECTORY
launch
DESTINATION share/${PROJECT_NAME})