RANGER MINI
  • RANGER MINI使用手册
  • 重要安全信息 Safety Information
  • 1 Ranger mini简介introduction
  • 2 基本介绍 The Basics
  • 3 使用和开发Getting Started
Powered by GitBook
On this page
  • 3.1使用与操作
  • 3.2 CAN接口协议
  • 3.3 固件升级
  • 3.4 Ranger mini ros package使用示例
  • 各sdk通信流程
  • 参数
  • 编译
  • 试运行
  • Ros Topic 示例
  • 订阅车辆实时输出信息
  • Sdk API 示例

Was this helpful?

3 使用和开发Getting Started

本部分主要介绍RANGER MINI平台的基本操作与使用,介绍如何通过外部CAN口,通过CAN总线协议来对RANGER MINI进行二次开发。

Previous2 基本介绍 The Basics

Last updated 3 years ago

Was this helpful?

3.1使用与操作

检查

检查RANGER MINI状态。

检查RANGER MINI是否有明显异常;如有,请联系售后支持;

初次使用时确认尾部电气面板中Q3(电源开关)是否被按下,如按下,请按下后释放,则处于释放状态,此时RANGER MINI处于断电状态。

启动和关机:尾部标有“STOP”标志的开关为电源开关,顺时针旋转可上电(电压表亮起),按下为关闭电源。启动后 需要等待底盘完成转向零位对准过程,方可进行控制操作。

充电:检查电池电压,正常电压范围为24~26.8V,如有“滴-滴滴...”连续蜂鸣器声音,表示电池电压过低,请及时充电。 本产品默认随车配备一个10A的充电器,将充电器的插头插入底盘左侧方品字充电插口,将充电器连接电源,将充电 器上开关打开,即可进入充电状态。

CAN线的连接

四轮四转底盘随车发货提供了1个航空插头公头,线的定义可参考下图:

红色 : VCC(电池正极)

黑色 :GND(电池负极)

蓝色 :CAN_L

黄色 :CAN_H

CAN指令控制的实现

正常启动RANGER MINI底盘,打开遥控器,然后将控制模式切换至指令控制,即将遥控器SWB模式选择拨至最上方, 此时RANGER MINI底盘会接受来自CAN接口的指令,同时主机也可以通过CAN总线回馈的实时数据,解析当前底盘 的状态,具体协议内容参考CAN通讯协议。

3.2 CAN接口协议

本产品中CAN通信标准采用的是CAN2.0B标准,通讯波特率为500K,报文格式采用MOTOROLA格式。通过外部CAN总线 接口可以进行控制模型切换和控制底盘移动的线速度以及转向角;底盘会实时反馈当前的运动状态信息(包括经过整 合处理的整机运动信息和各个轮子的详细运动信息)以及系统状态信息(包含自诊断错误码)。

指令名称

系统状态回馈指令

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

线控底盘

决策控制单元

0x211

20ms 无

数据长度

0x08

位置

功能

数据类型

说明

byte [0]

当前车体状态

unsigned int8

0x00 系统正常

0x02 系统异常

byte [1]

模式控制

unsigned int8

0x00 待机模式

0x01 CAN指令控制模式

0x03 遥控模式

byte [2]

byte [3]

电池电压高八位

电池电压低八位

unsigned int16

实际电压X 10 (精确到0.1V)

byte [4]

byte [5]

byte [6]

byte [7]

故障信息最高位

故障信息次高位

故障信息次低位

故障信息最低位

unsigned int32

详见表1

表格 1 故障信息说明表

故障信息说明

字节

位

含义

byte [4]

bit [0]~bit [7]

保留,默认0

bit [0]

左后转向零位校准状态(0:无故障 1:故障)

bit [1]

左前转向零位校准状态(0:无故障 1:故障)

bit [2]

右前转向零位校准状态(0:无故障 1:故障)

byte [5]

bit [3]

右后转向零位校准状态(0:无故障 1:故障)

bit [4]

转向校准过程超时或堵转(0:无故障 1:故障)

bit [5]

保留,默认0

bit [6]

保留,默认0

bit [7]

保留,默认0

bit [0]

驱动器状态错误(0:无故障1:故障)

bit [1]

上层通讯连接状态(0: 无故障 1: 故障)

bit [2]

5号电机驱动器通讯故障(0:无故障 1:故障)

byte [6]

bit [3]

6号电机驱动器通讯故障(0:无故障 1:故障)

bit [4]

7号电机驱动器通讯故障(0:无故障 1:故障)

bit [5]

8号电机驱动器通讯故障(0:无故障 1:故障)

bit [6]

过温保护(0:无故障 1:故障)

bit [7]

过流保护(0:无故障 1:故障)

故障信息说明

字节

位

含义

bit [0]

电池欠压故障(0:无故障 1:故障)保护电压为20.5V

bit [1]

预留,默认0

bit [2]

遥控器失联保护(0:正常,1:遥控器失联)

byte [7]

bit [3]

驱动1通讯故障(0:无故障,1:故障)

bit [4]

驱动2通讯故障(0:无故障,1:故障)

bit [5]

驱动3通讯故障(0:无故障,1:故障)

bit [6]

驱动4通讯故障(0:无故障,1:故障)

bit [7]

预留,默认0

运动控制回馈帧指令包含了当前车体的运动线速度、转向角度回馈

协议具体内容如下

指令名称

运动控制回馈指令

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

线控底盘

决策控制单元

0x221

20ms 无

数据长度

0x08

位置

功能

数据类型

说明

byte [0]

byte [1]

移动速度高八位

移动速度低八位

signed int16

实际速度X 1000 (单位0.001m/s)

byte [2]

保留

--

0X00

byte [3]

保留

--

0X00

byte [4]

保留

-

0X00

byte [5]

保留

--

0X00

byte[6]

byte [7]

转角高八位

转角低八位

signed int16

实际内转角X 100 (单位0.01°)

运动控制帧包含了线速度控制指令、转角控制指令,其具体协议内容如下:

指令名称

控制指令

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

决策控制单元

底盘节点

0x111

20ms 500ms

数据长度

0x08

位置

功能

数据类型

说明

byte [0]

byte [1]

线速度高八位

线速度低八位

signed int16

车体行进速度,单位mm/s(有效值+ -1500,当转向角度>20°时有效值±750;在前后阿克曼和斜移模式下生效)

byte [2]

保留

--

0X00

byte [3]

保留

--

0X00

byte[4]

byte [5]

自旋/横移速度高八位

自旋/横移速度低八位

signed int16

车体运动速度,单位mm/s (有效值+ -1000,在自旋和横移模式下生效)

byte [6]

byte [7]

转角高八位

转角低八位

signed int16

转向角,单位0.01°(有效值+ - 4000, 在前后阿克曼和斜移模式下生效)

如图3.2.1,当RANGER MINI底盘处于前后阿克曼模式时,反馈的转角为(α1+α2)/2,负值为左转方向,正值为右转 方向;反馈的速度为四轮速度平均值(即底盘运动线速度),负值为倒车,正值为前进。若需要查看各个轮子的详细 转角和速度信息,参看0X271和0X281反馈帧。

如图3.2.2,当ranger mini处于斜移模式时,反馈的转角为(α1+α2+α3+α4)/4,负值为左转方向,正值为右转方向; 反馈的线速度为四轮速度平均值,负值为倒车,正值为前进。若需要查看各个轮子的详细转角和速度信息,参看 0x271和0x281反馈帧。

当底盘处于自旋/横移模式时,转角为定值不可控,此时转角反馈为α1、α2、α3、α4四个实际角度的绝对值的平均 值。可通过指令控制底盘自旋/横移速度。

模式设定帧用于设定终端的控制接口,其具体协议内容如下。

指令名称

模式切换指令

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

决策控制单元

底盘节点

0x421

无 无

数据长度

0x01

位置

功能

数据类型

说明

byte [0]

控制模式

unsigned int8

0x00 待机模式

0x01 CAN指令模式

上电默认进入待机模式

控制模式说明:底盘在开机上电,遥控器未连接的情况下,控制模式默认是待机模式,此时底盘只接收控制模式指 令,其他指令不做响应,要使用CAN进行控制需要先切换到CAN指令模式。若打开遥控器,遥控器具有最高权限,可 以屏蔽指令的控制,切换控制模式。

状态置位帧用于清除系统错误,其具体协议内容如下。

指令名称

状态设定指令

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

决策控制单元

底盘节点

0x441

无 无

数据长度

0x01

位置

功能

数据类型

说明

byte [0]

错误清除指令

unsigned int8

0x00 清除全部非严重故障

0x01~0x08分别对应清除1~8号电机驱动器通讯故障

0x09 清除电池欠压故障,并尝试恢复动力电源 0x0a 清除遥控信号丢失故障

0x0b~0x0e 分别对应清除5~8号电机转向校准故障

0x0f 清除过流故障

0x10 清除过温故障

示例数据,以下数据仅供测试使用

1.小车以0.15m/S的速度前进

byte [0]

byte [1]

byte [2]

byte [3]

byte [4]

byte [5]

byte [6]

byte [7]

0x00

0x96

0x00

0x00

0x00

0x00

0x00

0x00

2.小车转向10°

byte [0]

byte [1]

byte [2]

byte [3]

byte [4]

byte [5]

byte [6]

byte [7]

0x00

0x00

0x00

0x00

0x00

0x00

0x03

0xe8

除了底盘的状态信息会进行反馈以外,底盘反馈的信息还包括四轮的转角和转速,电机的电流信息、编码器以及温度信息。 具体协议内容如下:

PS:在底盘中八个电机编号对应为:右前轮1号,右后轮2号,左后轮3号, 左前轮4号,右前转向5号,右后转向6号,左后转向7号,左前转向8号.

电机转速电流位置信息反馈

指令名称

电机驱动器高速信息反馈帧

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

线控底盘

决策控制单元

0x251~0x258

20ms 无

数据长度

0x08

位置

功能

数据类型

说明

byte [0]

byte [1]

电机转速高八位

电机转速低八位

signed int16

电机当前转速 单位RPM

byte [2]

byte [3]

电机电流高八位

电机电流低八位

signed int16

电机当前电流 单位0.1A

byte [4]

byte [5]

byte [6]

byte [7]

位置最高位

位置次高位

位置次低位

位置最低位

signed int32

电机当前位置 单位:脉冲数

电机温度电压及状态反馈

指令名称

电机驱动器低速信息反馈帧

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

线控底盘

决策控制单元

0x261~0x268

100ms 无

数据长度

0x08

位置

功能

数据类型

说明

byte [0]

byte [1]

驱动器电压高八位

驱动器电压低八位

unsigned int16

当前驱动器电压 单位0.1V

byte [2]

byte [3]

驱动器温度高八位

驱动器温度低八位

signed int16

单位1℃

byte [4]

电机温度

signed int8

单位1℃

byte [5]

驱动器状态

unsigned int8

详见表2

byte [6]

保留

--

0X00

byte [7]

保留

--

0X00

表格 2 驱动器状态

字节

位

含义

bit [0]

电源电压是否过低(0:正常 1:过低)

bit [1]

电机是否过温(0:正常 1:过温)

bit [2]

驱动器是否过流(0:正常 1:过流)

byte [5]

bit [3]

驱动器是否过温(0:正常 1:过温)

bit [4]

传感器状态(0:正常 1:异常)

bit [5]

驱动器错误状态(0:正常 1:错误)

bit [6]

驱动器使能状态(0:使能 1:失能)

bit [7]

保留

四轮转角反馈

指令名称

四轮转角信息反馈帧

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

线控底盘

决策控制单元

0x271

20ms 无

数据长度

0x08

位置

功能

数据类型

说明

byte [0]

byte [1]

5号转向转角高八位

5号转向转角低八位

signed int16

当前转角 单位0.01°

byte [2]

byte [3]

6号转向转角高八位

6号转向转角低八位

signed int16

当前转角 单位0.01°

byte [4]

byte [5]

7号转向转角高八位

7号转向转角低八位

signed int16

当前转角 单位0.01°

byte [6]

byte [7]

8号转向转角高八位

8号转向转角低八位

signed int16

当前转角 单位0.01°

四轮转速反馈

指令名称

四轮转速信息反馈帧

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

线控底盘

决策控制单元

0x281

20ms 无

数据长度

0x08

位置

功能

数据类型

说明

byte [0]

byte [1]

1号轮转速高八位

1号轮转速低八位

signed int16

当前转速 单位mm/s

byte [2]

byte [3]

2号轮转速高八位

2号轮转速低八位

signed int16

当前转速 单位mm/s

byte [4]

byte [5]

3号轮转速高八位

3号轮转速低八位

signed int16

当前转速 单位mm/s

byte [6]

byte [7]

4号轮转速高八位

4号轮转速低八位

signed int16

当前转速 单位mm/s

运动模型切换指令用于切换底盘运动模型,其具体协议内容如下

指令名称

当前运动模式回馈指令

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

线控底盘

决策控制单元

0x291

20ms 无

数据长度

0x02

位置

功能

数据类型

说明

byte [0]

当前底盘运动模式

unsigned int8

0x00前后阿克曼模式

0x01斜移模式

0x02自旋模式

0x03横移模式

byte [1]

是否处于运动模型切换过程

unsigned int8

0x00 切换完成

0x01 运动模型切换中

模型切换过程不响应速度控制指令

运动模型切换指令用于切换底盘运动模型,其具体协议内容如下

指令名称

运动模型切换指令

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

决策控制单元

底盘节点

0x141

无 无

数据长度

0x01

位置

功能

数据类型

说明

byte [0]

运动模式

unsigned int8

0x00前后阿克曼模式 (上电默认)

0x01斜移模式

0x02自旋模式

0x03横移模式

指令名称

BMS数据反馈

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

线控底盘

决策控制单元

0x361

500ms 无

数据长度

0x08

位置

功能

数据类型

说明

byte [0]

电池SOC

unsigned int8

范围 0~100

byte [1]

电池SOH

unsigned int8

范围 0~100

byte [2]

byte [3]

电池电压值高八位

电池电压值低八位

unsigned int16

单位:0.01V

byte [4]

byte [5]

电池电流值高八位

电池电流值低八位

signed int16

单位:0.1A

byte [6]

byte [7]

电池温度高八位

电池温度低八位

signed int16

单位:0.1℃

指令名称

BMS数据反馈

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

线控底盘

决策控制单元

0x362

500ms 无

数据长度

0x04

位置

功能

数据类型

说明

byte [0]

Alarm Status 1

unsigned int8

BIT1:过压 BIT2:欠压

BIT3:高温 BIT4:低温 BIT7:放电过流

byte [1]

Alarm Status 2

unsigned int8

BIT0:充电过流

byte [2]

Warning Status 1

unsigned int8

BIT1:过压 BIT2:欠压 BIT3:高温 BIT4:低温 BIT7:放电过流

byte [3]

Warning Status 2

unsigned int8

BIT0:充电过流

指令名称

转向零点设定指令

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

决策控制单元

底盘节点

0x362

无 无

数据长度

0x01

位置

功能

数据类型

说明

byte [0]

byte [1]

5号轮零点高八位

5号轮零点低八位

signed int16

零点偏移值设定 脉冲数;参考值-948

byte [2]

byte [3]

6号轮零点高八位

6号轮零点低八位

signed int16

零点偏移值设定 脉冲数;参考值970

byte [4]

byte [5]

7号轮零点高八位

7号轮零点低八位

signed int16

零点偏移值设定 脉冲数;参考值-970

byte [6]

byte [7]

8号轮零点高八位

8号轮零点低八位

signed int16

零点偏移值设定 脉冲数;参考值958

指令名称

转向零点设定反馈指令

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

决策控制单元

底盘节点

0x43B

无 无

数据长度

0x01

位置

功能

数据类型

说明

byte [0]

byte [1]

5号轮零点高八位

5号轮零点低八位

signed int16

零点偏移值设定 脉冲数;参考值-948

byte [2]

byte [3]

6号轮零点高八位

6号轮零点低八位

signed int16

零点偏移值设定 脉冲数;参考值970

byte [4]

byte [5]

7号轮零点高八位

7号轮零点低八位

signed int16

零点偏移值设定 脉冲数;参考值-970

byte [6]

byte [7]

8号轮零点高八位

8号轮零点低八位

signed int16

零点偏移值设定 脉冲数;参考值958

指令名称

转向零点查询指令

发送节点

接收节点

ID

周期(ms) 接收超时(ms)

决策控制单元

底盘节点

0x433

无 无

数据长度

0x01

位置

功能

数据类型

说明

byte [0]

查询当前各个转向零点

unsigned int8

固定值:0xAA 查询成功返回0x43B帧

3.3 固件升级

为了方便用户对四轮四转底盘所使用的固件版本进行升级,给客户带来更加完善的体验,四轮四转底盘提供了固件升级的 硬件接口以及与之对应的客户端软件。其客户端界面如下图所示。

升级准备

松灵CAN调试模块 X 1

micro USB线X 1

四轮四转底盘 X 1

电脑(WINDOWS 操作系统) X 1

升级过程

连接前保证机器人底盘电源处于断开状态;

使松灵can调试模块连接至底盘的航空插;

串口线连接至电脑;

打开客户端软件;

选择端口号;

四轮四转底盘上电,立即点击开始连接(四轮四转底盘 会在上电前3S等待,如果时间超过3S则会断开进入 应用程序);

若连接成功,会在文本框提示“连接成功”;

加载BIN文件;

点击升级,等待升级完成的提示即可;

断开串口线,底盘断电,再次通电即可。

3.4 Ranger mini ros package使用示例

ROS提供一些标准操作系统服务,例如硬件抽象,底层设备控制,常用功能实现,进程间消息以及数据包管理。ROS是基于一 种图状架构,从而不同节点的进程能接受,发布,聚合各种信息(例如传感,控制,状态,规划等等)。目前ROS主要支持 UBUNTU。

开发准备

硬件准备

CANlight can通讯模块 X1

Thinkpad E470 笔记本电脑 X1

AGILEX Ranger mini移动机器人底盘 X1

AGILEX Ranger mini 配套遥控器FS-i6s X1

AGILEX Ranger mini 尾部部航空插座 X1

使用示例环境说明

Ubuntu 16.04 LTS(此为测试版本,在Ubuntu 18.04 LTS测试过)

ROS Kinetic (后续版本亦测试过)

Git

硬件连接与准备

将Ranger mini尾部航空插头can线引出,将can线中can_H和can_L分别与CAN_TO_USB适配器相连;

打开Ranger mini移动机器人底盘电源开关;

将CAN_TO_USB连接至笔记本的usb口。连接示意如图所示。

ROS 安装和环境设置

测试CANABLE硬件与CAN 通讯

设置CAN-TO-USB适配器

使能 gs_usb 内核模块

$ sudo modprobe gs_usb

设置500k波特率和使能can-to-usb适配器

$ sudo ip link set can0 up type can bitrate 500000

如果在前面的步骤中没有发生错误,您应该可以使用命令立即查看can设备

$ ifconfifig -a

安装并使用can-utils来测试硬件

$ sudo apt install can-utils

若此次can-to-usb已经和Ranger mini相连,且小车已经开启的情况下,使用下列指令可以监听来自Ranger mini底盘的数据了

$ candump can0

各sdk通信流程

•ugv_sdk 通过 can 协议和车辆底盘通信

•ranger_ros 包通过调用 GetRangerState 接口获取最新的机器信息,通过调 用 SetMotionCommand 来设置车轮的线速度和角度(注意是轮子,不是车整 体的), 通过SetMotionMode 来改变运动模式

•ranger mini 有4种运动模式,参考手册agilex develop manuals

•发布 ranger_setting topic 可以设置运动模式

•订阅 ranger_status 可以获取机器当前状态

参数

查看 ranger_base/launch/ranger_mini_base.launch

•israngermini : ranger mini 或者 ranger pro车型,暂时只有 ranger mini一种车型

•port_name: can端口名称,通常是 can0

•simulated_robot: 是否为仿真机器

•odom_frame: tf树中odometry 帧的名字

•base_frame: tf树中base link 帧的名字

•odomtopicname: odometry topic 的名字

•pubodomtf: 是否发布odometry 帧的 tf transformation

编译

依赖的内容:

•ROS1 MELODIC 或者更新版本

例如你的ROS工作空间为

~/agilex_ws

\# install ugv_sdk

cd ~/agilex_ws/src

git clone https://github.com/westonrobot/ugv_sdk.git

cd ugv_sdk

git checkout -b v2.x origin/v2.x

cd ../

catkin_make install --pkg ugv_sdk

# source the packages

source devel/setup.bash

\# install ranger_ros

cd ~/agilex_ws/src/

git clone https://github.com/westonrobot/ranger_ros.git

# install the ascent library at fifirst

cd ranger_ros/ranger_base/ascent

mkdir -p build && cd build && cmake -DBUILD_TESTING=OFF .. && sudo make install

cd ~/agilex_ws/

catkin_make install # or just catkin_make

# if you catch error: ranger_msgs/RangerSetting.h: No such fifile or directory

# then install ranger_msgs fifirst

catkin_make install --pkg ranger_msgs

# for install

catkin_make install

试运行

# run ranger_ros

cd ~/agilex_ws

source devel/setup.bash

roslaunch ranger_bringup ranger_minimal.launch

使用键盘进行控制

默认的运动模式是: 前后阿克曼模式

# if you want to remote control the car by keyboard

sudo apt install ros-$ROS_DISTRO-teleop-twist-keyboard

roslaunch ranger_bringup ranger_teleop_keyboard.launch

Ros Topic 示例

•输入: 车辆整体的线速度和航向角

•输出: 车辆整体线速度,X方向速度,Y方向速度,角速度,航向角,旋转半径

PUBLISH TOPIC 来控制车辆

////----------------CONTROL BY ROS TOPIC---------------------------------

ROS::PUBLISHER MOTION_MODE =

NODE.ADVERTISE<RANGER_MSGS::RANGERSETTING>("/RANGER_SETTING", 1);

RANGER_MSGS::RANGERSETTING SETTING;

SETTING.MOTION_MODE = RANGER_MSGS::RANGERSETTING::MOTION_MODE_ACKERMAN;

MOTION_MODE.PUBLISH(SETTING);

////------------------MOVE BY ROS TOPIC --------------------------------

ROS::PUBLISHER MOVE_CMD =

NODE.ADVERTISE<GEOMETRY_MSGS::TWIST>("/CMD_VEL", 10);

GEOMETRY_MSGS::TWIST CMD;

CMD.LINEAR.X = 0.1; // THE MOTOR WILL RUN AT 0.1M/S

CMD.ANGULAR.Z = 30.0 / 180.0 * M_PI; // THE HEADING ANGLE OF THE CAR

// PUBLISH ROBOT STATE AT 50HZ WHILE LISTENING TO TWIST COMMANDS

ROS::RATE RATE(50);

WHILE (ROS::OK()) {

ROS::SPINONCE();

// /CMD_VEL TOPIC MUST SEND AT 50HZ, EVEN STOP NEED SEND 0M/S

MOVE_CMD.PUBLISH(CMD);

RATE.SLEEP();

}

也可以通过命令行方式发布TOPIC来控制

\# 0 ACKRMANN, 1 SLIDE, 2 ROUND, 3 SLOPING

\# 0 前后阿克曼,1 斜移, 2 自旋, 3 侧移

ROSTOPIC PUB -1 /RANGER_SETTING RANGER_MSGS/RANGERSETTING -- '[0, 0, SETTING_-

FRAME]' '1'

ROSTOPIC PUB /CMD_VEL GEOMETRY_MSGS/TWIST --RATE 50 '[0.1, 0.0, 0.0]' '[0.0, 0.0,

0.52358]' # 0.52358 = 30 DEGREE

订阅车辆实时输出信息

ROS::SUBSCRIBER STATUS_SUB = NODE.SUBSCRIBE<RANGER_MSGS::RANGERSTATUS>(

"/RANGER_STATUS", 10, STATUSCALLBACK);

VOID STATUSCALLBACK(RANGER_MSGS::RANGERSTATUS::CONSTPTR MSG) {

STD::COUT << "LINEAR VELOCITY: " << MSG->LINEAR_VELOCITY << STD::ENDL;

STD::COUT << "ANGULAR VELOCITY: " << MSG->ANGULAR_VELOCITY << STD::ENDL;

STD::COUT << "X DIRECTION LINEAR VELOCITY: " << MSG->X_LINEAR_VEL << STD::ENDL;

STD::COUT << "Y DIRECTION LINEAR LINEAR VELOCITY: " << MSG->Y_LINEAR_VEL << STD::ENDL;

STD::COUT << "ROTATE RADIUS: " << MSG->MOTION_RADIUS << STD::ENDL;

STD::COUT << "CAR HEADING ANGLE: " << MSG->STEERING_ANGLE << STD::ENDL;

// ...ETC

}

用 ROSTOPIC 来查看输出的事实信息

ROSTOPIC ECHO /RANGER_STATUS

Sdk API 示例

0.使能通过 CAN 控制

ROBOT->CONNECT("CAN0");

ROBOT->ENABLECOMMANDEDMODE();

1.设置运动模式

ROBOT->CONNECT("CAN0");

ROBOT->ENABLECOMMANDEDMODE();

// 0 ARCKMANN 1 SLIDE 2 ROUND, 3 SLOPING

// 0 前后阿克曼 1 横移 2 自旋 3 侧移

ROBOT->SETMOTIONMODE(0);

// ROBOT->SETMOTIONMODE(1);

// ROBOT->SETMOTIONMODE(2);

// ROBOT->SETMOTIONMODE(3);

2.设置轮子的线速度和角度

ROBOT->SETMOTIONCOMMAND(0.1, 30.0/180.0 * M_PI); // STEER ANGLE = 30°

// OR WRITE THEM IN A FUNCTION

VOID ACKERMANN() {

ROBOT->SETMOTIONMODE(0);

// OR

ROBOT->SETMOTIONMODE(RANGERSETTING::MOTION_MODE_ACKERMAN);

L_V = 0.1; // M/S

ANGLE_Z = 30 / 180 * M_PI; // RAD

}

VOID SLIDE() {

ROBOT->SETMOTIONMODE(1);

// OR

ROBOT->SETMOTIONMODE(RANGERSETTING::MOTION_MODE_SLIDE);

L_V = 0.1; // M/S

ANGLE_Z = 30 / 180 * M_PI; // RAD

}

VOID ROUND() {

ROBOT->SETMOTIONMODE(2);

// OR

ROBOT->SETMOTIONMODE(RANGERSETTING::MOTION_MODE_ROUND);

L_V = 0.1;

// ANGLE_Z IS NOT USED

}

VOID SLOPING() {

ROBOT->SETMOTIONMODE(3);

// OR

ROBOT->SETMOTIONMODE(RANGERSETTING::MOTION_MODE_SLOPING);

L_V = 0.1;

// ANGLE_Z IS NOT USED

}

使用 ODOMETRY

SUBSCRIBE /ODOM TOPIC

安装具体可以参考

更多内容请参考

更多内容请参考

更多内容参考

更多内容参考

http://wiki.ros.org/kinetic/Installation/Ubuntu
RANGER_ROS/RANGER_EXAMPLES/SRC/INPUT.CPP
RANGER_ROS/RANGER_EXAMPLES/SRC/OUTPUT.CPP
RANGER_ROS/RANGER_EXAMPLES/SRC/CHANGE_THE_MODE.CPP
RANGER_ROS/RANGER_EXAMPLES/SRC/CONTROL_THE_CAR.CPP
图3.1 航空插头示意图
图3.2.1ranger mini阿克曼结构
图3.2.2ranger mini斜移结构