基础知识
- 生成文件tree
- ROSLAUNCH 的.launch/XML 语法
- C语言中 int main(int argc,char *argv[])的两个参数详解
- param name=“robot_description” command=" $(find xacro)/xacro --inorder ’ $(arg model)’ 到底什么意思
- 由浅到深理解ROS(5)- launch启动文件的理解与编写
- 使用tree命令导出文件夹/文件的目录树
- ROS_INFO & ROS_DEBUG的区别
- rxconsole弃用->使用rqt_console
由启动语句分析
roslaunch ur_modern_driver ur3_ros_control.launch robot_ip:=192.168.1.100
ur3_ros_control.launch
- 调试功能
- 输入参数
- 载入模型 – ur3_upload.launch
- 启动节点(ur_driver节点硬件接口)- ur_ros_wrapper.cpp
- 读取参数 – ur3_controllers.yaml 让所有节点去访问
- 生成控制器管理器
- load other controller 目的暂不得而知
- robot_state_publisher
<?xml version="1.0"?>
<launch>
<!-- GDB functionality -->
<!-- GDB 一种调试用的工具罢了 -->
<arg name="debug" default="false" />
<!-- 如果为假 如果为真 -->
<arg unless="$(arg debug)" name="launch_prefix" value="" />
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
<arg name="robot_ip"/>
<arg name="limited" default="false"/>
<arg name="min_payload" default="0.0"/>
<arg name="max_payload" default="3.0"/>
<arg name="prefix" default="" /> <!-- 前缀 -->
<arg name="max_velocity" default="10.0"/> <!-- [rad/s] -->
<arg name="base_frame" default="$(arg prefix)base" /> <!-- 前缀 -->
<arg name="tool_frame" default="$(arg prefix)tool0_controller" />
<!-- robot model -->
<include file="$(find ur_description)/launch/ur3_upload.launch">
<arg name="limited" value="$(arg limited)"/>
</include>
<!-- Load hardware interface -->
<!-- 命名 包的名字 可执行程序的名字 -->
<node name="ur_hardware_interface" pkg="ur_modern_driver" type="ur_driver" output="log" launch-prefix="$(arg launch_prefix)">
<!-- 声明到了参数服务器中 -->
<param name="robot_ip_address" type="str" value="$(arg robot_ip)"/>
<param name="min_payload" type="double" value="$(arg min_payload)"/>
<param name="max_payload" type="double" value="$(arg max_payload)"/>
<param name="max_velocity" type="double" value="$(arg max_velocity)"/>
<param name="use_ros_control" type="bool" value="True"/>
<param name="servoj_gain" type="double" value="750" />
<param name="prefix" value="$(arg prefix)" />
<param name="base_frame" type="str" value="$(arg base_frame)"/>
<param name="tool_frame" type="str" value="$(arg tool_frame)"/>
</node>
<!-- Load controller settings -->
<!--读取参数 -->
<rosparam file="$(find ur_modern_driver)/config/ur3_controllers.yaml" command="load"/>
<!-- 以下应该都是ros control的东西了 -->
<!-- spawn controller manager -->
<!-- 生成控制器管理器 -->
<node name="ros_control_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" args="joint_state_controller force_torque_sensor_controller pos_based_pos_traj_controller" />
<!-- load other controller -->
<node name="ros_control_controller_manager" pkg="controller_manager" type="controller_manager" respawn="false"
output="screen" args="load vel_based_pos_traj_controller" />
<!-- Convert joint states to /tf tranforms -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"/>
</launch>
ur3_upload.launch
<?xml version="1.0"?>
<launch>
<arg name="limited" default="false" doc="If true, limits joint range [-PI, PI] on all joints." />
<arg name="transmission_hw_interface" default="hardware_interface/PositionJointInterface" />
<param unless="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_description)/urdf/ur3_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)" /> <!-- 传递给xacro文件的 -->
<param if="$(arg limited)" name="robot_description" command="$(find xacro)/xacro --inorder '$(find ur_description)/urdf/ur3_joint_limited_robot.urdf.xacro' transmission_hw_interface:=$(arg transmission_hw_interface)" />
</launch>
数据流
使用rqr_graph查看节点间的关系图
其他都很好理解,主要问题是spawner节点打开的controller——pos_based_pos_traj_controller是如何体现在下面的(moveit->硬件)
?->ur_hardware_interface实现实例化来使用。
实际上是通过 action机制传递在一起的。
可以看出moveit是客户
ur_modern_driver(UR的驱动的底层实现方式)
-
关键是找到他是如何加载controller的。
-
他的消息机制是如何实现的。
-
URscripts是如何发送的。
-
controller的功能是如何实现的
代码结构解析如下:
.
├── CMakeLists.txt
├── config
│ ├── ur10_controllers.yaml
│ ├── ur3_controllers.yaml
│ └── ur5_controllers.yaml
├── include
│ └── ur_modern_driver
│ ├── do_output.h
│ ├── robot_state.h
│ ├── robot_state_RT.h
│ ├── ur_communication.h
│ ├── ur_dashboard.h
│ ├── ur_driver.h
│ ├── ur_hardware_interface.h
│ └── ur_realtime_communication.h
├── launch
│ ├── ur10_bringup_compatible.launch
│ ├── ur10_bringup_joint_limited.launch
│ ├── ur10_bringup.launch
│ ├── ur10_ros_control.launch
│ ├── ur3_bringup_joint_limited.launch
│ ├── ur3_bringup.launch
│ ├── ur3_ros_control.launch
│ ├── ur5_bringup_compatible.launch
│ ├── ur5_bringup_joint_limited.launch
│ ├── ur5_bringup.launch
│ ├── ur5_ros_control.launch
│ └── ur_common.launch
├── LICENSE
├── package.xml
├── README.md
├── src
│ ├── do_output.cpp
│ ├── robot_state.cpp
│ ├── robot_state_RT.cpp
│ ├── ur_communication.cpp
│ ├── ur_dashboard.cpp
│ ├── ur_driver.cpp
│ ├── ur_hardware_interface.cpp
│ ├── ur_realtime_communication.cpp
│ └── ur_ros_wrapper.cpp // main函数
├── test_move.py
└── tree.txt
5 directories, 38 files
这里主要看src下的文件结构即可。
ur_ros_wrapper.cpp
- main 函数所在
- 声明了类RosWrapper来实现各种功能
- 其中的循环等待线程机制见《ROS机器人开发实践》P40
- wrapper 读取参数并且通过ur_driver【一堆set】设置参数
int main(int argc, char **argv) {
bool use_sim_time = false;
std::string host;
int reverse_port = 50001;//http://wiki.ros.org/ur_driver/hydro 机器人返回给PC的端口
ros::init(argc, argv, "ur_driver");
ros::NodeHandle nh;
if (ros::param::get("use_sim_time", use_sim_time)) {
print_warning("use_sim_time is set!!");
}
if (!(ros::param::get("~robot_ip_address", host))) {
if (argc > 1) {
print_warning(
"Please set the parameter robot_ip_address instead of giving it as a command line argument. This method is DEPRECATED");
//请设置参数robot_ip_address,而不是将其作为命令行参数提供。此方法已弃用
host = argv[1];
} else {
print_fatal(
"Could not get robot ip. Please supply it as command line parameter or on the parameter server as robot_ip");
exit(1);
}
}
if ((ros::param::get("~reverse_port", reverse_port))) {
if((reverse_port <= 0) or (reverse_port >= 65535)) {
print_warning("Reverse port value is not valid (Use number between 1 and 65534. Using default value of 50001");
reverse_port = 50001;
}
} else
reverse_port = 50001;
RosWrapper interface(host, reverse_port);
ros::AsyncSpinner spinner(3); //多线程处理多个接收
spinner.start();
ros::waitForShutdown();
interface.halt();
exit(0);
}
ur_driver.cpp
- 对机器人的一些设置操作,写URScripts然后加入到发送队列中(此时就转到了ur_realtime_communication中)。
class UrDriver {
private:
double maximum_time_step_;
double minimum_payload_;
double maximum_payload_;
std::vector<std::string> joint_names_;
std::string ip_addr_;
const int MULT_JOINTSTATE_ = 1000000;
const int MULT_TIME_ = 1000000;
const unsigned int REVERSE_PORT_;
int incoming_sockfd_;
int new_sockfd_;
bool reverse_connected_;
double servoj_time_;
bool executing_traj_;
double firmware_version_;
double servoj_lookahead_time_;
double servoj_gain_;
public:
UrRealtimeCommunication* rt_interface_;
UrCommunication* sec_interface_;
UrDashboard* dash_interface_;
UrDriver(std::condition_variable& rt_msg_cond,
std::condition_variable& msg_cond, std::string host,
unsigned int reverse_port = 50007, double servoj_time = 0.016, unsigned int safety_count_max =
12, double max_time_step = 0.08, double min_payload = 0.,
double max_payload = 1., double servoj_lookahead_time=0.03, double servoj_gain=300.);
bool start();
void halt();
void setSpeed(double q0, double q1, double q2, double q3, double q4,
double q5, double acc = 100.);
bool doTraj(std::vector<double> inp_timestamps,
std::vector<std::vector<double> > inp_positions,
std::vector<std::vector<double> > inp_velocities);
void servoj(std::vector<double> positions, int keepalive = 1);
void stopTraj();
bool uploadProg();
bool openServo();
void closeServo(std::vector<double> positions);
std::vector<double> interp_cubic(double t, double T,
std::vector<double> p0_pos, std::vector<double> p1_pos,
std::vector<double> p0_vel, std::vector<double> p1_vel);
std::vector<std::string> getJointNames();
void setJointNames(std::vector<std::string> jn);
void setToolVoltage(unsigned int v);
void setFlag(unsigned int n, bool b);
void setDigitalOut(unsigned int n, bool b);
void setAnalogOut(unsigned int n, double f);
bool setPayload(double m);
void setMinPayload(double m);
void setMaxPayload(double m);
void setServojTime(double t);
void setServojLookahead(double t);
void setServojGain(double g);
};
ur_realtime_communication.h
do_output.h
定义输出