1 四足机器人感知方案:

四足机器人强烈依赖感知来实现高性能的越障,对于四足机器人盲目爬行(Blind Walk)步态来说其是四足机器人最基本的要求,即在摆动高度固定、满足运动空间约束的条件下,四足机器人通过灵敏的着地判断与伺服力柔顺控制就能实现通过障碍地形,这部分以Spotmini和Vision60在盲爬下就能实现可靠稳定的上下台阶,该部分主要依赖可靠的力觉着地判断和可靠的MPC控制,但我认为更重要的是处理好在阶跃地形时的状态估计保证力控制指令的平滑连续、以及摆动相机保证时刻有腿支撑产生控制量。

对于高于摆动高度的地形基本的力伺服控制框架下引入SLAM并主动选择落足位置,当然最简单的是只考虑对落足点的规划,但在地下离散度很高的情况下太偏离质心的落足位置会造成较大的扰动,因此需要进一步引入对质心运动轨迹的规划,如Anymal引入深度强化学习或者在MPC控制中引入地形约束来实现,这也是四足机器人目前主要的研究方向,对于环境的感知四足机器人与无人车不同,更关注局部地图的高程信息,以SpotMini为例其采用全向深度视觉的方案来实现定位与建图,并进一步实现落足点的最优选择。

对于向Anymal-C这样明确针对工业应用的平台,其会在视觉的基础上进一步增加雷达,对于近距离地图的构建雷达会出现扫描盲区,而通过深度视觉补偿能更好的描述地形起伏信息,同时其刷新率也更换能满足四足机器人高动态步态规划的需求,因此在现有的四足机器人感知方案中主要依赖雷达来解决户外大范围空间下的精确定位并提供里程计数据,同时融合视觉深度点云来构建局部的高程地图,并进一步结合语义识别来区分安全落足区域。

同样上述里程计+局部建图的方案在低成本四足机器人中应用的更加广泛,如MIT Cheetha其采用了RealSense 435+T265的方案,国内很多的小型机器人感知系统也采用双深度相机的方案,如小米铁蛋、宇树A1。另外也有采用之前提到的雷达+视觉的方案,这样更多是行业级的平台如绝影Lite系列。

综上,纯视觉和雷达+视觉的方案是目前的主流,二者在优缺点上各有特色:

(1) 纯视觉方案:成本低但稳定性差,视觉方案最难解决的还是特征点丢失下的飘逸问题,解决这个问题主要靠采用多视角相机来构建,但对处理器性能的要求会高很多,另外成本也相应增加,因此在室内环境下可能视觉的方案更加合适,另外视觉系统对光照、纹理以及深度估计一致性的要求对相关的VSLAM算法鲁棒性要求很高;

(2) 纯雷达方案:纯雷达方案能有效解决机器人本体的定位问题,因此现在很多无人车依靠单个雷达就能实现可靠的自动挡驾驶,加上目前很多16线雷达的价格也大大增加,使得小型化、低功耗的雷达被大量部署在机器人中,对于四足机器人来说采用雷达提供可靠精确的里程计信息,则无人驾驶现成的全局SLAM和导航算法可以非常容易的进行迁移,但与车辆不同的是四足机器人需要构建局部高程图来进行越障控制,而雷达过于稀疏的点云会造成最终建立的高程图存在缺口;

(3) 雷达+视觉方案:通过视觉和雷达相互补充能很好地满足足式机器人的导航和建图需求,基于雷达能解决纯视觉定位鲁棒性差、有效探测距离近等问题,而通过深度视觉能很好地探测近距离下的地形信息,补充雷达地图点云稀疏的问题;

2 Pholcus的感知配置:

Pholcus机器人的感知系统采用了目前常用的SLAM小车方案,即采用深度相机+2D雷达+里程计融合的方案,采用RTAB框架来实现对深度图像、雷达点云以及足式里程计的融合,由于Pholcus主要设计的理念是构建一个面向城市环境自主搜索的低成本蜂群机器人平台,因此在上述硬件的基础上又增加了左右两路侧向深度视觉后置FPV视觉以及面阵UWB测距模块,其原因是:

(1)左右侧向深度视觉

四足机器人侧向稳定性是所有控制回路中最差的部分,对于12自由度机器人来说其上下台阶时最难以控制就是侧向速度,同时该通道还与横滚强烈耦合,在城市环境下存在很多狭窄通道,而机器人在不知道侧向距离的前提下仅依赖FPV操控是无法完成超视距控制任务的,如发生与墙壁碰撞非常容易造成足式平台的摔倒,因此对于超视距下的遥控需要全向的视觉和俯视操控视角,这一点从SpotMini的操控界面中也可以看出:

SpotMini俯视图操控类似汽车

(2)后置FPV和测距模块

由于Pholcus是一个典型的8自由度机器人,其转向效率比较低,因此和传统履带车类似采用差速转向,这样在狭窄的区域中非常容易出现没法原地转向掉头的情况,因此需要布置后向FPV相机来完成反向遥控,同时增加测距雷达模块,提示与墙壁的距离;

(3)面阵UWB测距侧向模块

小型机器人未来主要以集群控制为主,因此需要具有独立于传统雷达或视觉感知的传感器,这类似很多小说中的心灵感应,通过UWB面阵测距知道僚机相对自己的近程位置;另外,可以基于这样的传感器来实现不依赖视觉和雷达SLAM下快速、高效地对人员的主动跟随;

由于成本限制,Pholcus采用的方案只是为了探寻面向城市探索任务需求,四足机器人到底需要部署哪些传感器,因此采用的感知设备都是比较低成本、常见的方案,对于最终Pholcus可以采用更好的深度相机(RealSense)、图像处理器(AGX)以及多线激光雷达(ETH球形雷达),但对于探索Pholcusz这样轻小型机器人的感知系统框架,下面采用的方案已经能够保证基本功能和验证算法的部署:

如上图所示的原理图,感知部分核心处理器采用JetsonNano,通过USB连接了2D雷达和前置深度相机运行RTAB实现建图定位,左右两路相机通过USB-HUB扩展,后置FPV单目相机使用最后一个USB口采集,通过电池降压的5V给路由器和交换机供电,而JetsonNano单独采用大电流独立降压模块保证上述设备的功耗需求,这里的深度相机采用了Astra奥比中光的Atras深度模块:

雷达采用了TOF 2D雷达,其相比Rplidar重量轻而且雷达扫描转动也不明显,相关参数也更加优异:

路由器采用了GL.iNet,其具有三个LAN口可以连接交换机和主控制器,同时还能中继手机WIFI热点实现ROS系统的更新,同时具有一个USB口可以扩展4G网卡,后续实现内网穿透,当然在实际使用中可以将其外壳拆除将原装的2.4G天线更换为更大增益的机柜天线:

这里所有机器人本体内部的主控、感知都由该路由器管理,而外部设备或载荷设备的网络通信都通过另外的交互机进行扩展:

UWB-AOA采用了空循环Nooploop的测距侧向模块,其可以提高180°朝向内标签的距离与偏角度,从而计算相对的极坐标位置,其由主控直接采集这样在感知系统失效下也能实现人员跟随。

最终,完成上述设备的组装Pholcus也具有了SpotMini一样全向视觉感知能力,当然也仅仅只能满足简单算法研究娱乐的需求-W-:

3 多路Astra相机驱动ROS Launch:

相比市面上现有的RTAB方案雷达小车,由于增加了2路深度相机,因此需要采用Astra多相机Launch的方案,这里提供了一个我测试用的3深度相机Launch,其中左右两侧相机目前没法输出RGB相机图像原因仍在排查,运行后个深度相机将输出各自独立话题的深度图像,这里参考了冰达机器人的ROS源码在Astra ROS SDK中修改;

<launch>
  <!-- "camera" should uniquely identify the device. All topics are pushed down
       into the "camera" namespace, and it is prepended to tf frame ids. -->
  <arg name="camera"      default="camera"/>
  <arg name="publish_tf"  default="true"/>
  <arg name="3d_sensor"   default="astra"/>  <!-- stereo_s_u3, astrapro, astra -->

  <arg name="device_1_prefix"   default="r"/>
  <arg name="device_2_prefix"   default="l"/>
  <arg name="device_3_prefix"   default=""/>
  <arg name="device_1_id"       default="AC2MC13006E"/>
  <arg name="device_2_id"       default="AC2MC13003Y"/>
  <arg name="device_3_id"       default="16112910925"/>
  <arg name="has_uvc_serial"    default="false"/>

  <!-- Factory-calibrated depth registration -->
  <arg name="depth_registration"              default="false"/>
  <arg     if="$(arg depth_registration)" name="depth" value="depth_registered" />
  <arg unless="$(arg depth_registration)" name="depth" value="depth" />

  <!-- Processing Modules -->
  <arg name="rgb_processing"                  default="true"/>
  <arg name="ir_processing"                   default="false"/>
  <arg name="depth_processing"                default="true"/>
  <arg name="depth_registered_processing"     default="false"/>
  <arg name="disparity_processing"            default="false"/>
  <arg name="disparity_registered_processing" default="false"/>

  <!-- Worker threads for the nodelet manager -->
  <arg name="num_worker_threads" default="4" />

  <include file="$(find astra_camera)/launch/$(arg 3d_sensor).launch">
    <arg name="camera"                          value="$(arg camera)_$(arg device_1_prefix)"/>
    <arg name="device_id"                       value="$(arg device_1_id)"/>
    <arg name="uvc_serial"                      value="$(arg device_1_id)" if="$(eval has_uvc_serial == true)"/>
    <arg name="bootorder"                       value="1"/>
    <arg name="devnums"                         value="3"/>
    <arg name="publish_tf"                      value="$(arg publish_tf)"/>
    <arg name="depth_registration"              value="$(arg depth_registration)"/>
    <arg name="num_worker_threads"              value="$(arg num_worker_threads)" />
    <!-- add index if uvc does not have serial -->
    <!--arg name="index"                           value="0"/ -->

    <!-- Processing Modules -->
    <arg name="rgb_processing"                  value="$(arg rgb_processing)"/>
    <arg name="ir_processing"                   value="$(arg ir_processing)"/>
    <arg name="depth_processing"                value="$(arg depth_processing)"/>
    <arg name="depth_registered_processing"     value="$(arg depth_registered_processing)"/>
    <arg name="disparity_processing"            value="$(arg disparity_processing)"/>
    <arg name="disparity_registered_processing" value="$(arg disparity_registered_processing)"/>
  </include>
  
  <include file="$(find astra_camera)/launch/$(arg 3d_sensor).launch">
    <arg name="camera"                          value="$(arg camera)_$(arg device_2_prefix)"/>
    <arg name="device_id"                       value="$(arg device_2_id)"/>
    <arg name="uvc_serial"                      value="$(arg device_2_id)" if="$(eval has_uvc_serial == true)"/>
    <arg name="bootorder"                       value="2"/>
    <arg name="devnums"                         value="3"/>
    <arg name="publish_tf"                      value="$(arg publish_tf)"/>
    <arg name="depth_registration"              value="$(arg depth_registration)"/>
    <arg name="num_worker_threads"              value="$(arg num_worker_threads)" />
    <!-- add index if uvc does not have serial -->
    <!--arg name="index"                           value="1"/ -->

    <!-- Processing Modules -->
    <arg name="rgb_processing"                  value="$(arg rgb_processing)"/>
    <arg name="ir_processing"                   value="$(arg ir_processing)"/>
    <arg name="depth_processing"                value="$(arg depth_processing)"/>
    <arg name="depth_registered_processing"     value="$(arg depth_registered_processing)"/>
    <arg name="disparity_processing"            value="$(arg disparity_processing)"/>
    <arg name="disparity_registered_processing" value="$(arg disparity_registered_processing)"/>
  </include>


    <node pkg="uvc_camera" type="uvc_camera_node" name="uvc_camera1" output="screen">
    <param name="width" type="int" value="320" />
    <param name="height" type="int" value="240" />
    <param name="device" type="string" value="/dev/video-back" />
    <param name="format " type="string" value="jpeg" />
    <param name="topic_cam" type="string" value="image_raw_back/compressed" />
    </node>

    <!--robot bast type use different tf value-->
    <arg name="base_type"       default="$(env BASE_TYPE)" />
    <!-- robot frame -->
    <arg name="base_frame"       default="base_footprint" />    
    <arg name="camera_type"       default="$(env CAMERA_TYPE)" />   
    <arg name="camera_frame" default="camera_link"/>  

  <include file="$(find robot_vslam)/launch/camera/astrapro.launch">
    <arg name="device_id"                       value="$(arg device_3_id)"/>
    <arg name="uvc_serial"                      value="$(arg device_3_id)" if="$(eval has_uvc_serial == true)"/>
    <arg name="bootorder"                       value="3"/>
    <arg name="devnums"                         value="3"/>
    <!-- add index if uvc does not have serial -->
    <!-- arg name="index"                           value="2"/ -->
  </include>

    <group if="$(eval camera_type == 'astrapro')">
        <group if="$(eval base_type == '4WD')">
            <node pkg="tf" type="static_transform_publisher" name="base_footprint_to_camera" 
                args="0.115 0.0 0.25 0.0 0.0 0.0 $(arg base_frame) $(arg camera_frame) 20">
            </node>
        </group>
        <group if="$(eval base_type == '4WD_OMNI')">
            <node pkg="tf" type="static_transform_publisher" name="base_footprint_to_camera"
                args="0.115 0.0 0.25 0.0 0.0 0.0 $(arg base_frame) $(arg camera_frame) 20">
            </node>
        </group>
        <group if="$(eval base_type == 'NanoRobot_Pro')">
            <node pkg="tf" type="static_transform_publisher" name="base_footprint_to_camera"
                args="0.2 0.0 0.08 0.0 0.0 0.0 $(arg base_frame) $(arg camera_frame) 20">
            </node>
        </group>
        <group if="$(eval base_type == 'NanoCar_Pro')">
            <node pkg="tf" type="static_transform_publisher" name="base_footprint_to_camera"
                args="0.20 0.0 0.07 0 0.0 0.0 $(arg base_frame) $(arg camera_frame) 20">
            </node>
        </group>
        <group if="$(eval base_type == 'Race182')">
            <node pkg="tf" type="static_transform_publisher" name="base_footprint_to_camera"
                args="0.180 0.0 0.168 0 0.0 0.0 $(arg base_frame) $(arg camera_frame) 20">
            </node>
        </group>   
        <group if="$(eval base_type == 'NanoOmni')">
            <node pkg="tf" type="static_transform_publisher" name="base_footprint_to_camera"
                args="0.100 0.0 0.168 0 0.0 0.0 $(arg base_frame) $(arg camera_frame) 20">
            </node>
        </group>               
    </group>

  <!--<node pkg="tf" type="static_transform_publisher" name="multiastra" args="0 0 0 0 0.72 0 /camera_01_link /camera_02_link 100"/>-->

</launch>

另外由于RTAB需要雷达/scan信息的单位为而LD06雷达输出的是毫米,因此这里也给出修改其SDK源码部分的代码:

#include <iostream>
#include "cmd_interface_linux.h"
#include <stdio.h>
#include "lipkg.h"
#include <ros/ros.h>
#include <sensor_msgs/LaserScan.h>
#include "tofbf.h"
#include <string>

int main(int argc , char **argv)
{
	ros::init(argc, argv, "product");
	ros::NodeHandle nh;                    /* create a ROS Node */

 	
	LiPkg * lidar = new LiPkg;
    std::string frame_id="base_laser_link";
    CmdInterfaceLinux cmd_port;
    std::vector<std::pair<std::string, std::string> > device_list;
    std::string port_name;
    cmd_port.GetCmdDevices(device_list);

    ros::NodeHandle nh_private("~");
    nh_private.param<std::string>("frame_id", frame_id, "base_laser_link");
    //nh_private.param<bool>("inverted", inverted, false);
 

    for (auto n : device_list)
    {
        std::cout << n.first << "    " << n.second << std::endl;
        if(strstr(n.second.c_str(),"CP2102"))
        {
            port_name = n.first;
        }
    }

	if(port_name.empty())
	{
		std::cout<<"Can't find LiDAR LD06"<< std::endl;
	}

	std::cout<<"FOUND LiDAR_LD06_MOCO"  <<std::endl;
	cmd_port.SetReadCallback([&lidar](const char *byte, size_t len) {
		if(lidar->Parse((uint8_t*)byte, len))
		{
			lidar->AssemblePacket();  
		}
	});

	if(cmd_port.Open(port_name))
		std::cout<<"LiDAR_LD06 MOCO started successfully "  <<std::endl;
	
	ros::Publisher lidar_pub = nh.advertise<sensor_msgs::LaserScan>("scan", 1); /*create a ROS topic */
	
	while (ros::ok())
	{
		if (lidar->IsFrameReady())
		{
			sensor_msgs::LaserScan scan_msg=lidar->GetLaserScan();
   			scan_msg.header.frame_id = frame_id;
			scan_msg.range_min=0.16;//1000.;
			scan_msg.range_max=15;//1000.;
			
			sensor_msgs::LaserScan scan_msg_temp=scan_msg;
			if(1){//revert
			//std::cout<<"Can't find LiDAR LD06"<< std::endl;

			for(int i=0;i<sizeof(scan_msg.ranges);i++){
				scan_msg.ranges[sizeof(scan_msg.ranges)-1-i] =scan_msg_temp.ranges[i]/1000.;
				scan_msg.intensities[sizeof(scan_msg.ranges)-1-i] = scan_msg_temp.intensities[i];

			}
                          }else{
			for(int i=0;i<sizeof(scan_msg.ranges);i++)
				scan_msg.ranges[i] /=1000.;
                          }	

			lidar_pub.publish(scan_msg);  // Fixed Frame:  lidar_frame
			lidar->ResetFrameReady();
		}
	}
    return 0;
}

4 视觉感知与足式里程计资料:

最后,对于上述RTAB方案来说由于目前市面上给出的大多是差速转向或4轮驱动小车,因此需要采用四足机器人来提供/odom里程计话题,这里就不能不提到足式里程计与视觉感知系统的融合,可以参考的方案主推还是MIT的KF多支接触点的单刚体框架,当前其简化了很多问题,实际机器人中存在的足端滑移以及在大落差起伏地形上的状态估计是非常重要的问题,下面给出一些个人觉得比较好的论文和研究资料:

ETH视觉导航框架
IIT视觉落足与高层图
视觉雷达足式里程计融合
链接:https://pan.baidu.com/s/1oufD473QbrXkkdTc9L7Rfw 
提取码:rzx4 
--来自百度网盘超级会员V2的分享

5 结语:

这次为Pholcus搭建了基本VSLAM+2D雷达感知框架,让其具有了全向感知与导航能力,同时借鉴SpotMini和8自由度平台的特点,将所有传感器和控制器都保护在了机体内部,感知采用现在SLAM四轮小车主流的RTAB方案,Pholcus已经可以完成自主导航与主动避障,并通过采集多路相机实现了全向FPV遥控,为超视距操控提供了非常好的基础。但实际上2路深度视觉信息并未完全使用,而且后置UWB跟随俯视数字孪生操控局部高程图都还没涉及,欢迎关注Pholcus的进展,后续将上述硬件基础上实现人员跟随以及高程图下的主动落足选择等高级技能。