前言

之前我做机器人仿真一直是在 windows 上,利用 webots+vs 进行仿真的,但是在 vs 上进行的仿真,移植到硬件上时需要改动的东西太多,几乎得重新写一遍,所以打算在 linux 上利用 ros 进行仿真。但是问题又来了,ros 中比较常用的仿真的软件就是 gazebo,但是 gazebo 的电机模块的力矩控制在我测试之后好像是有问题的,一旦施加力矩就会疯转。后来偶然间发现 linux 上是可以使用 webots 的,而且网络上的配置资料不算少,所以就打算使用 webots 来进行仿真。

ros 安装

webots 安装

直接去官网上下载安装包即可,不要直接在主页上下载最新版的,那个不一定适配你的 ubuntu 版本,所以需要点 Download 右边的箭头,选择 Older version,从里面找到适合自己版本的安装包,不然就无法安装

1
sudo dpkg -i webots_202xx_xxx.deb

有时候会出点问题,导致安装失败,可以利用下面的指令来尝试修复依赖关系并完成未完成的配置

1
sudo apt install -f

安装完成之后,需要设置环境变量,在 ~/.bashrc 文件中最后一行添加以下指令,如果用的是 zsh 终端,就可以在 ~/.zshrc 文件最后一行添加下面指令,由于是用安装包安装的,默认安装路径为 /usr/local/webots

1
export WEBOTS_HOME=/usr/local/webots

之后即可进入 webots ,需要注意的是如果下载的 webots 版本比较高的话,webots 的资源包是在线加载的,但是在线加载确实很慢,而且需要科学上网工具,很难受。所以给出的解决办法就是从官方 github 仓库里,找到下载的对应版本的 webots ,找到对应版本的 assets-Rxxxx.zip 文件,下载下来之后,将其解压并且替换掉文件夹 ~/.cache/Cyberbotics/Webots/assets 即可。注意这个 .cache 是隐藏文件,需要在文件管理器中按下 Ctrl+H 快捷键显示隐藏文件,而且直接复制过去需要权限,就很麻烦,不如直接用指令将对应文件夹内的东西移动过去。

1
sudo mv assets-Rxxxx/* ~/.cache/Cyberbotics/Webots/assets/

另外新版本本地文档也没了,还需要从 webots 官方仓库 里找到文件夹 docs ,如果直接从网上下载的话,需要下载的东西很多,用的时间也很长,所以推荐一个小工具 DownGit ,进入网站之后,将 https://github.com/cyberbotics/webots/tree/master/docs 复制到 url 框中,点击 Download 即可下载。下载完成之后,将其解压替换掉 webots 安装目录下的 docs 文件夹即可。这个也是一样,需要权限,一般 webots 的安装目录为 /usr/local/webots/

1
sudo mv docs/* /usr/local/webots/docs/

如果没有这个文件夹 /usr/local/webots/docs/ 的话,就创建这个文件夹之后再次使用上述指令。

1
sudo mkdir /usr/local/webots/docs

webots_ros 安装

在终端输入指令,记住要安装对应 ros 版本的 webot_ros,我这里用的是 ros-noetic ,所以对应的就是 ros-noetic-webots-ros

1
sudo apt install ros-noetic-webots-ros

webots_ros

weobots 设置

首先可以进入 webots 创建世界,创建需要仿真控制的机器人,之后将机器人的 controller 设置为 ros

ros 设置

webots_ros 之前是有官方文档的,但是现在好像没了,但是可以还是有 webots_ros 这个库的,里面是一些案例,有兴趣的话可以看看

1
git clone https://github.com/cyberbotics/webots_ros.git

在 webots_ros 中有一些需要用到的文件,需要复制到自己的功能包中,如下,这两个文件夹里就是 webots_ros 提供的那些关于传感器的服务和消息类型,实际上在安装过 webots_ros 之后,这两个文件夹也存在于 ${WEBOTS_HOME}/projects/default/controllers/ros/include 文件夹之下

1
2
sudo cp webots_ros/srv package_name/srv
sudo cp webots_ros/msg package_name/msg

需要修改 CMakeLists.txt 文件,添加消息和服务类型,这些都是在控制 webots 机器人时需要用到的。

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
add_message_files(
FILES
BoolStamped.msg
Float64Stamped.msg
Int32Stamped.msg
Int8Stamped.msg
RadarTarget.msg
RecognitionObject.msg
StringStamped.msg
)
add_service_files(
FILES
camera_get_focus_info.srv
camera_get_info.srv
camera_get_zoom_info.srv
display_draw_line.srv
display_draw_oval.srv
display_draw_pixel.srv
display_draw_polygon.srv
display_draw_rectangle.srv
display_draw_text.srv
display_get_info.srv
display_image_copy.srv
display_image_delete.srv
display_image_load.srv
display_image_new.srv
display_image_paste.srv
display_image_save.srv
display_set_font.srv
field_get_bool.srv
field_get_color.srv
field_get_count.srv
field_get_float.srv
field_get_int32.srv
field_get_node.srv
field_get_rotation.srv
field_get_string.srv
field_get_type.srv
field_get_type_name.srv
field_get_vec2f.srv
field_get_vec3f.srv
field_import_node.srv
field_import_node_from_string.srv
field_remove_node.srv
field_remove.srv
field_set_bool.srv
field_set_color.srv
field_set_float.srv
field_set_int32.srv
field_set_rotation.srv
field_set_string.srv
field_set_vec2f.srv
field_set_vec3f.srv
get_bool.srv
get_float_array.srv
get_float.srv
get_int.srv
get_string.srv
get_uint64.srv
get_urdf.srv
gps_decimal_degrees_to_degrees_minutes_seconds.srv
lidar_get_frequency_info.srv
lidar_get_info.srv
lidar_get_layer_point_cloud.srv
lidar_get_layer_range_image.srv
motor_set_control_pid.srv
mouse_get_state.srv
node_add_force_or_torque.srv
node_add_force_with_offset.srv
node_get_center_of_mass.srv
node_get_contact_point.srv
node_get_field.srv
node_get_id.srv
node_get_number_of_contact_points.srv
node_get_name.srv
node_get_orientation.srv
node_get_parent_node.srv
node_get_position.srv
node_get_static_balance.srv
node_get_status.srv
node_get_type.srv
node_get_velocity.srv
node_remove.srv
node_reset_functions.srv
node_move_viewpoint.srv
node_set_visibility.srv
node_set_velocity.srv
pen_set_ink_color.srv
range_finder_get_info.srv
receiver_get_emitter_direction.srv
robot_get_device_list.srv
robot_set_mode.srv
robot_wait_for_user_input_event.srv
save_image.srv
set_bool.srv
set_float.srv
set_float_array.srv
set_int.srv
set_string.srv
skin_get_bone_name.srv
skin_get_bone_orientation.srv
skin_get_bone_position.srv
skin_set_bone_orientation.srv
skin_set_bone_position.srv
speaker_is_sound_playing.srv
speaker_speak.srv
speaker_play_sound.srv
supervisor_get_from_def.srv
supervisor_get_from_id.srv
supervisor_movie_start_recording.srv
supervisor_set_label.srv
supervisor_virtual_reality_headset_get_orientation.srv
supervisor_virtual_reality_headset_get_position.srv
)

需要修改 package.xml 文件,需要在添加依赖的地方添加这两条语句,就是用于自定义消息类型的

1
2
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>

可以为 webots 写一个 launch 文件来启动对应的世界,一般是将 webots 的世界文件保存在功能包路径下的 webots/world 文件夹下,这个 launch 文件的功能就是打开 world_name 这个世界,然后启动 webots 的键盘节点,这样就有键盘输入了,就能在代码里写读取键盘来控制机器人了

1
2
3
4
5
6
7
8
9
10
11
12
13
<?xml version="1.0"?>
<launch>
<!-- start Webots -->
<arg name="no_gui" default="false," doc="Start Webots with minimal GUI" />
<include file="$(find webots_ros)/launch/webots.launch">
<arg name="mode" value="realtime" />
<arg name="no_gui" value="$(arg no_gui)" />
<arg name="world" value="$(find package_name)/webots/world/world_name.wbt" />
</include>

<arg name="auto_close" default="false" doc="Startup mode" />
<node name="keyboard_teleop" pkg="webots_ros" type="keyboard_teleop" required="$(arg auto_close)" />
</launch>

一些消息和服务类型

下面说以下我用的比较多的消息和服务类型,我刚开始用的时候,几乎在网络上找不到对应的文章,之后是自己通过启动 webots 之后,查看消息和服务的列表来做的,这里作为记录吧

电机相关

  • 电机传感器反馈使能服务

    • 服务名称: /robot_name/position_sensor_name/enable
    • 消息类型: webots::set_int
    • 传输的消息是传感器的反馈频率

      1
      2
      3
      4
      5
      ros::ServiceClient joint_sensor_enable = nh.serviceClient<webots_ros::set_int>("/robot_name/position_sensor_name/enable");
      webots_ros::set_int enable_time_step;
      joint_sensor_enable.request.value = TIME_STEP; // 世界的步长,需要与 webots 中设置的世界步长一致
      force_feedback_enable.call(enable_time_step);
      if (!enable_time_step.response.success) ROS_INFO("joint_sensor_enable failed");
  • 电机力矩反馈使能服务

    • 服务名称: /robot_name/motor_name/torque_feedback_sensor/enable
    • 消息类型: webots::set_int
    • 传输的消息是传感器的反馈频率

      1
      2
      3
      4
      5
      ros::ServiceClient force_feedback_enable = nh.serviceClient<webots_ros::set_int>("/robot_name/motor_name/torque_feedback_sensor/enable");
      webots_ros::set_int enable_time_step;
      enable_time_step.request.value = TIME_STEP; // 世界的步长,需要与 webots 中设置的世界步长一致
      force_feedback_enable.call(enable_time_step);
      if (!enable_time_step.response.success) ROS_INFO("force_feedback_enable failed");
  • 电机位置获取消息订阅

    • 消息名称: /robot_name/motor_name/value
    • 反馈函数形式: void IOROS::callback(const webots_ros::Float64Stamped::ConstPtr &value) 其中的 value 形参就是接收到的消息
    • 需要等待订阅者成功订阅

      1
      2
      3
      4
      5
      6
      7
      ros::Subscriber motor_get_pos = nh.subscribe("/robot_name/motor_name/value", 1, pos_callback);
      while (motor_get_pos.getNumPublishers() == 0)
      ;

      void pos_callback(const webots_ros::Float64Stamped::ConstPtr &value) {
      float position = value->data;
      }
  • 电机速度获取请求服务

    • 服务名称: /robot_name/motor_name/get_velocity
    • 消息类型: webots::get_float

      1
      2
      3
      4
      ros::ServiceClient motor_get_vel = nh.serviceClient<webots_ros::get_float>("/quadruped/rf_hip_joint/get_velocity");
      webots_ros::get_float get_velocity_srv;
      motor_get_vel.call(get_velocity_srv);
      float motor_vel = get_velocity_srv.response.value;
  • 电机力矩获取消息订阅

    • 消息名称: /robot_name/motor_name/torque_feedback_sensor/value
    • 反馈函数形式: void IOROS::rf_hip_tor_callback(const webots_ros::Float64Stamped::ConstPtr &value) 其中 value 形参就是接收到的消息

      1
      2
      3
      4
      5
      6
      7
      ros::Subscriber motor_get_tor = nh.subscribe("/robot_name/motor_name/torque_feedback_sensor/value", 1, tor_callback);
      while (motor_get_tor.getNumPublishers() == 0)
      ;

      void tor_callback(const webots_ros::Float64Stamped::ConstPtr &value) {
      float torque = value->data;
      }
  • 电机位置设置请求服务

    • 服务名称: /robot_name/motor_name/set_position
    • 消息类型: webots::set_float
    • 传输的消息是电机位置值

      1
      2
      3
      4
      ros::ServiceClient motor_set_pos = nh.serviceClient<webots_ros::set_float>("/robot_name/motor_name/set_position");
      webots_ros::set_float pos;
      pos.request.value = position;
      motor_set_pos.call(pos);
  • 电机速度设置请求服务

    • 服务名称: /robot_name/motor_name/set_velocity
    • 消息类型: webots::set_float
    • 传输的消息是电机速度值

      1
      2
      3
      4
      ros::ServiceClient motor_set_vel = nh.serviceClient<webots_ros::set_float>("/robot_name/motor_name/set_velocity");
      webots_ros::set_float vel;
      vel.request.value = velocity;
      motor_set_vel.call(vel);
  • 电机力矩设置请求服务

    • 服务名称: /robot_name/motor_name/set_torque
    • 消息类型: webots::set_float
    • 传输的消息是电机力矩值

      1
      2
      3
      4
      ros::ServiceClient motor_set_tor = nh.serviceClient<webots_ros::set_float>("/robot_name/motor_name/set_torque");
      webots_ros::set_float tor;
      tor.request.value = torque;
      motor_set_tor.call(tor);
  • 电机力设置请求服务

    • 服务名称: /robot_name/motor_name/set_force
    • 消息类型: webots::set_float
    • 传输的消息是电机力矩值

      1
      2
      3
      4
      ros::ServiceClient motor_set_tor = nh.serviceClient<webots_ros::set_float>("/robot_name/motor_name/set_force");
      webots_ros::set_float force;
      force.request.value = force_value;
      motor_set_tor.call(force);

imu 相关

  • imu 使能服务

    • 服务名称: /robot_name/imu_name/enable
    • 消息类型: webots::set_int
    • 传输的消息是传感器的反馈频率

      1
      2
      3
      4
      5
      ros::ServiceClient imu_enable = nh.serviceClient<webots_ros::set_int>("/robot_name/imu_name/enable");
      webots_ros::set_int enable_time_step;
      enable_time_step.request.value = TIME_STEP; // 世界的步长,需要与 webots 中设置的世界步长一致
      imu_enable.call(enable_time_step);
      if (!enable_time_step.response.success) ROS_INFO("imu_enable false");
  • imu 四元数消息订阅

    • 消息名称: /robot_name/imu_name/quaternion
    • 回调函数形式: void imu_callback(const sensor_msgs::Imu::ConstPtr &values)

      1
      2
      3
      4
      5
      6
      7
      8
      9
      10
      ros::Subscriber imu_sub = nh.subscribe("/robot_name/imu_name/quaternion", 1, imu_callback);
      while (imu_sub.getNumPublishers() == 0)
      ;

      void imu_callback(const sensor_msgs::Imu::ConstPtr &values) {
      quat[0] = values->orientation.x;
      quat[1] = values->orientation.y;
      quat[2] = values->orientation.z;
      quat[3] = values->orientation.w;
      }

gyro 相关

  • gyro 使能服务

    • 服务名称: /robot_name/gyro_name/enable
    • 消息类型: webots::set_int
    • 传输的消息是传感器的反馈频率

      1
      2
      3
      4
      5
      ros::ServiceClient gyro_enable = nh.serviceClient<webots_ros::set_int>("/robot_name/gyro_name/enable");
      webots_ros::set_int enable_time_step;
      enable_time_step.request.value = TIME_STEP; // 世界的步长,需要与 webots 中设置的世界步长一致
      gyro_enable.call(enable_time_step);
      if (!enable_time_step.response.success) ROS_INFO("gyro_enable false");
  • gyro 角速度消息订阅

    • 消息名称: /robot_name/gyro_name/values
    • 反馈函数形式: void gyro_callback(const sensor_msgs::Imu::ConstPtr &values)

      1
      2
      3
      4
      5
      6
      7
      8
      9
      ros::Subscriber gyro_sub = nh.subscribe("/robot_name/gyro_name/values", 1, gyro_callback);
      while (gyro_sub.getNumPublishers() == 0)
      ;

      void gyro_callback(const sensor_msgs::Imu::ConstPtr &values) {
      gyro[0] = values->angular_velocity.x;
      gyro[1] = values->angular_velocity.y;
      gyro[2] = values->angular_velocity.z;
      }

accel 相关

  • accel 使能服务

    • 服务名称: /robot_name/accel_name/enable
    • 消息类型: webots::set_int
    • 传输的消息是传感器的反馈频率

      1
      2
      3
      4
      5
      ros::ServiceClient accel_enable = nh.serviceClient<webots_ros::set_int>("/robot_name/accel_name/enable");
      webots_ros::set_int enable_time_step;
      enable_time_step.request.value = TIME_STEP; // 世界的步长,需要与 webots 中设置的世界步长一致
      accel_enable.call(enable_time_step);
      if (!enable_time_step.response.success) ROS_INFO("accel_enable false");
  • accel 加速度消息订阅

    • 消息名称: /robot_name/accel_name/values
    • 反馈函数形式: void accel_callback(const sensor_msgs::Imu::ConstPtr &values)

      1
      2
      3
      4
      5
      6
      7
      8
      9
      ros::Subscriber accel_sub = nh.subscribe("/quadruped/accel/values", 1, accel_callback);
      while (accel_sub.getNumPublishers() == 0)
      ;

      void accel_callback(const sensor_msgs::Imu::ConstPtr &values) {
      accel[0] = values->angular_velocity.x;
      accel[1] = values->angular_velocity.y;
      accel[2] = values->angular_velocity.z;
      }

小结

实际上可以看出来,其实还挺简单的,而且很有规律,例如需要设置值的服务,消息类型就是 set_ 开头的,需要获取数据的服务,消息类型就是 get_ 开头的,所以最难的就是看看复制到功能包里的 srv ·和 msg 文件。

总结

由于这个是之前研究的,最近才整理了一下,所以可能有错误,参考即可,主要还是要靠自己多研究研究