ROS开发(二)——添加电机驱动话题(电机驱动)

这是一个通过ROS通信控制maxon电机的教程,电机通信是通过CAN通信

maxon电机

型号 额定电压 额定电流 额定转速 额定转矩 功率 重量 直径
EC-i40(496652) 36V 1.61A 6080rpm 78.2mNm 50W 180g 40mm
EC-i40(496655) 36V 2.73A 6450rpm 129mNm 70W 250g 40mm
EC-i40(496661) 36V 2.72A 3950rpm 207rpm 100W 390g 40mm

1.CAN通信命令

2. 编写接受话题数据包

2.1 MCP2515 SPI转CAN通信

由于树莓派上没有CAN通信接口,MCP2515将SPI控制信号转为CAN通信信号,添加BCM2835库,该库是用于调用SPI等资源的库

- wget http://www.airspayce.com/mikem/bcm2835/bcm2835-1.57.tar.gz 
- tar zxvf bcm2835-1.57.tar.gz
- cd bcm2835-1.57.tar.gz
- ./configure
- make
- sudo make install

2.2 编写FindBCM2835.cmake文件

同样在/opt/cmake-3.12.1/Modules文件夹中添加该cmake文件,用于寻找到BCM2835的库

  • vim FindBCM2835.cmake
    1
    2
    3
    4
    5
    6
    7
    8
    9
    10
    11
    12
    13
    find_path (BCM2835_INCLUDE_DIR bcm2835.h )
    find_library (BCM2835_LIBRARY NAMES bcm2835)

    set (BCM2835_LIBRARIES ${BCM2835_LIBRARY} )
    set (BCM2835_INCLUDE_DIRS ${BCM2835_INCLUDE_DIR} )

    include(FindPackageHandleStandardArgs)
    # handle the QUIETLY and REQUIRED arguments and set BCM2835_FOUND to TRUE
    # if all listed variables are TRUE
    find_package_handle_standard_args(BCM2835 DEFAULT_MSG
    BCM2835_LIBRARY BCM2835_INCLUDE_DIR)

    mark_as_advanced (BCM2835_INCLUDE_DIR BCM2835_LIBRARY )

2.3 编写一个MOTOR库用于将CAN控制命令封装

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
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
#define	CAN_10Kbps	0x31
#define CAN_25Kbps 0x13
#define CAN_50Kbps 0x09
#define CAN_100Kbps 0x04
#define CAN_125Kbps 0x03
#define CAN_250Kbps 0x01
#define CAN_500Kbps 0x00

#define SCK 14
#define SI 12
#define SO 13
#define CS 10 //CE0
#define INTIN 3
#define RST 4
#define TXREQ_M 0b11110111
#define CH 0

#include <mcp2515.h>
#include <bcm2835.h>
#include <wiringPi.h>
#include <stdio.h>
#include <stdlib.h>
#include <time.h>
#include "motor.h"
//写一个字节
void MOTOR::MCP2515_WriteByte(unsigned char addr,unsigned char dat){
unsigned char buf = CAN_WRITE;
char spiDat[] = {CAN_WRITE,addr,dat};
digitalWrite(CS,LOW);
bcm2835_spi_transfern(spiDat,3);
digitalWrite(CS,HIGH);
}
//读一个字节
unsigned char MOTOR::MCP2515_ReadByte(unsigned char addr){
unsigned char rByte = 0;
char spiDat[] = {CAN_READ,addr,0xff};
digitalWrite(CS,LOW);
bcm2835_spi_transfern(spiDat,3);
digitalWrite(CS,HIGH);
rByte = spiDat[2];
return rByte;
}
void MOTOR::MCP2515_Reset(void){
digitalWrite(CS,LOW);
delay(100);
char spiDat[]={CAN_RESET};
bcm2835_spi_transfern(spiDat,1);
digitalWrite(CS,HIGH);
delay(100);
}
void MOTOR::MCP2515_Init(void){
unsigned char temp=1;
MCP2515_Reset();
MCP2515_WriteByte(CNF1,CAN_125Kbps);
MCP2515_WriteByte(CNF2,0x80|PHSEG1_3TQ|PRSEG_1TQ);
MCP2515_WriteByte(CNF3,PHSEG2_3TQ);
MCP2515_WriteByte(RXB0CTRL,0x60);
MCP2515_WriteByte(RXB0DLC,8);
MCP2515_WriteByte(RXF0SIDH,0x0A);
MCP2515_WriteByte(RXF0SIDL,0x58);
MCP2515_WriteByte(RXM0SIDH,0xFF);
MCP2515_WriteByte(RXM0SIDL,0xE0);
MCP2515_WriteByte(RXB0SIDH,0x00);
MCP2515_WriteByte(RXB0SIDL,0x00);
MCP2515_WriteByte(CANINTE,0x01);
MCP2515_WriteByte(CANINTF,0x00);
MCP2515_WriteByte(CANCTRL,REQOP_NORMAL|CLKOUT_ENABLED);
temp=MCP2515_ReadByte(CANSTAT);
while(OPMODE_NORMAL!=(temp & 0xE0))
{
MCP2515_WriteByte(CANCTRL,REQOP_NORMAL|CLKOUT_ENABLED);
temp=MCP2515_ReadByte(CANSTAT);
}
}

void MOTOR::CAN_Send_Buffer(unsigned char *CAN_TX_Buf,unsigned char len) {
unsigned char dly,j;
int count=0;
while(count<len){
dly=0;
while((MCP2515_ReadByte(TXB0CTRL)&0x08) && (dly<50)){
bcm2835_delay(1);
dly++;
}
for(j=0;j<8;){
MCP2515_WriteByte(TXB0D0+j,CAN_TX_Buf[count++]);
j++;
if(count>=len) break;
}
MCP2515_WriteByte(TXB0DLC,j);
// printf("%d\n",j);
digitalWrite(CS,LOW);
MCP2515_WriteByte(TXB0CTRL,0x08);
digitalWrite(CS,HIGH);
}
}

unsigned char MOTOR::CAN_Receive_Buffer(unsigned char *CAN_RX_Buf){
unsigned char i=0,len=0,temp=0;
temp = MCP2515_ReadByte(CANINTF);
// printf("CANINTF: %02x\n",temp);
if(temp & 0x01){
len=MCP2515_ReadByte(RXB0DLC);
while(i<len)
{
CAN_RX_Buf[i]=MCP2515_ReadByte(RXB0D0+i);
i++;
}

}
MCP2515_WriteByte(CANINTF,0);
return len;
}

void MOTOR::bcm2835_SPISetup(void){
if (!bcm2835_init()){
printf("bcm2835_init failed. Are you running as root??\n");
exit(1);
}
if (!bcm2835_spi_begin()){
printf("bcm2835_spi_begin failed. Are you running as root??\n");
exit(1);
}
bcm2835_spi_setBitOrder(BCM2835_SPI_BIT_ORDER_MSBFIRST); // The default
bcm2835_spi_setDataMode(BCM2835_SPI_MODE0); // The default
bcm2835_spi_setClockDivider(BCM2835_SPI_CLOCK_DIVIDER_65536); // The default
bcm2835_spi_chipSelect(BCM2835_SPI_CS0); // The default
bcm2835_spi_setChipSelectPolarity(BCM2835_SPI_CS0, LOW); // the default
}

int MOTOR::CAN_ReciveByte(unsigned char CANID,unsigned char * data_Buff){
MCP2515_WriteByte(RXB0CTRL,0x20);
MCP2515_WriteByte(RXF0SIDH,(CANID>>3)&0x1F);
MCP2515_WriteByte(RXF0SIDL,(CANID<<5)&0xE0);
int len = CAN_Receive_Buffer((unsigned char*)data_Buff);
printf("data=%s\n",data_Buff);
return len;
}

//激活CAN总线
int MOTOR::CAN_Start(void){
if(wiringPiSetup() < 0)
return 1;
pinMode(CS,OUTPUT);
pinMode(INTIN,INPUT);
pinMode(RST,OUTPUT);
printf("wiringPi Setup OK\n");
bcm2835_SPISetup();
printf("SPI Setup OK\n");
MCP2515_Init();
AriseAllMotor();
return 0;
}
//使能速度模式
void MOTOR::ENABLEID_speed(unsigned char CANID){
MCP2515_WriteByte(TXB0SIDH,(CANID>>3)&0x1F|0xc0);
MCP2515_WriteByte(TXB0SIDL,(CANID<<5)&0xE0);
unsigned char buff[24]={0x22,0x60,0x60,0x00,0x03,0x00,0x00,0x00,
0x22,0x40,0x60,0x00,0x06,0x00,0x00,0x00,
0x22,0x40,0x60,0x00,0x0f,0x00,0x00,0x00};
CAN_Send_Buffer(buff,24);
}
//使能位置模式
void MOTOR::ENABLEID_position(unsigned char CANID){
MCP2515_WriteByte(TXB0SIDH,(CANID>>3)&0x1F|0xc0);
MCP2515_WriteByte(TXB0SIDL,(CANID<<5)&0xE0);
unsigned char buff[24]={0x22,0x60,0x60,0x00,0x01,0x00,0x00,0x00,
0x22,0x40,0x60,0x00,0x06,0x00,0x00,0x00,
0x22,0x40,0x60,0x00,0x0f,0x00,0x00,0x00};
CAN_Send_Buffer(buff,24);
}
void MOTOR::AriseAllMotor(void){
MCP2515_WriteByte(TXB0SIDH,0x00);
MCP2515_WriteByte(TXB0SIDL,0x20);
unsigned char canStart[]={0x00,0x01,0x00};
CAN_Send_Buffer(canStart,3);
delay(100);
}
//速度模式
int MOTOR::CAN_VelocityMode(unsigned char CANID,int velocityOct){
MCP2515_WriteByte(TXB0SIDH,(CANID>>3)&0x1F|0xc0);
MCP2515_WriteByte(TXB0SIDL,(CANID<<5)&0xE0);
unsigned char velocityHexH;
unsigned char velocityHexL;
if(velocityOct > 0){
velocityHexH = (velocityOct>>8)&0xff;
velocityHexL = velocityOct&0xff;
}
else return 1;
unsigned char buff[16]={0x22,0xff,0x60,0x00,velocityHexL,velocityHexH,0x00,0x00,
0x22,0x40,0x60,0x00,0x0f,0x00,0x00,0x00};
CAN_Send_Buffer(buff,16);
return 0;
}

//位置模式
int MOTOR::CAN_PositionMode(unsigned char CANID,int positionOct){
MCP2515_WriteByte(TXB0SIDH,(CANID>>3)&0x1F|0xc0);
MCP2515_WriteByte(TXB0SIDL,(CANID<<5)&0xE0);
unsigned char positionHexH = (positionOct>>8)&0xff;
unsigned char positionHexL = positionOct&0xff;
unsigned char buff[16]={0x22,0x7a,0x60,0x00,positionHexL,positionHexH,0x00,0x00,
0x22,0x40,0x60,0x00,0x0f,0x00,0x00,0x00};
CAN_Send_Buffer(buff,16);
return 0;
}
void MOTOR::Stop(unsigned char CANID){
MCP2515_WriteByte(TXB0SIDH,(CANID>>3)&0x1F|0xc0);
MCP2515_WriteByte(TXB0SIDL,(CANID<<5)&0xE0);
unsigned char buff[8]={0x22,0x40,0x60,0x00,0x0b,0x00,0x00,0x00};
CAN_Send_Buffer(buff,8);
}
void MOTOR::Halt(unsigned char CANID){
MCP2515_WriteByte(TXB0SIDH,(CANID>>3)&0x1F|0xc0);
MCP2515_WriteByte(TXB0SIDL,(CANID<<5)&0xE0);
unsigned char buff[8]={0x22,0x40,0x60,0x00,0x0f,0x01,0x00,0x00};
CAN_Send_Buffer(buff,8);
}
MOTOR::~MOTOR(void){
bcm2835_spi_end();
bcm2835_close();
}
void MOTOR::test(void)//测试电机
{
CAN_Start();
ENABLEID_speed(0x01);
CAN_VelocityMode(0x01,2000);
exit(0);
// CAN_PositionMode(0x01,2000);
}

2.4编写motor.h头文件

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
#ifndef _MOTOR_H
#define _MOTOR_H

class MOTOR
{
public:
MOTOR(void){}
~MOTOR(void);
int CAN_Start(void);//使能CAN
void AriseAllMotor(void);//唤醒电机
void ENABLEID_speed(unsigned char CANID);//使能速度模式
int CAN_VelocityMode(unsigned char CANID,int velocityOct);//速度模式设置参数
void ENABLEID_position(unsigned char CANID);//使能位置模式
int CAN_PositionMode(unsigned char CANID,int positionOct);//位置模式设置参数
void Stop(unsigned char CANID);//急停
void Halt(unsigned char CANID);//停止

void CAN_Send_Buffer(unsigned char *CAN_TX_Buf,unsigned char len);//向主机上发送一段数据
unsigned char CAN_Receive_Buffer(unsigned char *CAN_RX_Buf);//全部接受一段数据
int CAN_ReciveByte(unsigned char CANID,unsigned char * data_Buff);//接受来自ID的数据
void test(void);//电机测试
private:
unsigned char CAN_R_Buffer[8];
unsigned char CAN_R_Buffer2[8];
void bcm2835_SPISetup(void);
void MCP2515_Reset(void);
void MCP2515_Init(void);
void MCP2515_WriteByte(unsigned char addr,unsigned char dat);
unsigned char MCP2515_ReadByte(unsigned char addr);
};
#endif

2.5 创建motor_control话题订阅包

-  roscreate-pkg motor_control roscpp

2.6 编写CmakeLists.txt文件

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
cmake_minimum_required(VERSION 2.8.3)
project(motor_control)
add_compile_options(-std=c++11)
find_package(catkin REQUIRED COMPONENTS
roscpp
std_msgs
sensor_msgs
)

find_package(Boost REQUIRED COMPONENTS system)
find_package(BCM2835 REQUIRED)
find_package(WiringPi REQUIRED)

catkin_package(
INCLUDE_DIRS include
# LIBRARIES motor_control
CATKIN_DEPENDS roscpp std_msgs sensor_msgs
# DEPENDS system_lib
)

include_directories(
include
${catkin_INCLUDE_DIRS}
)

add_executable(${PROJECT_NAME}_node src/motor_control_node.cpp src/motor.cpp)

target_link_libraries(${PROJECT_NAME}_node
${catkin_LIBRARIES}
${WIRINGPI_LIBRARIES}
${BCM2835_LIBRARY}
)

2.7 编写package.xml文件

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
<?xml version="1.0"?>
<package>
<name>motor_control</name>
<version>0.0.0</version>
<description>The motor_control package</description>
<maintainer email="shisanchuan@todo.todo">shisanchuan</maintainer>
<license>TODO</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>sensor_msgs</build_depend>

<run_depend>roscpp</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>sensor_msgs</run_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>

2.8 在include文件夹中添加头文件

2.9 编写motor_control_node.cpp文件

由于电机拥有四个,将四个定义为right_ID1right_ID2left_ID1left_ID2,通过订阅话题实现控制电机

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
#include <std_msgs/Int16.h>
#include <std_msgs/Empty.h>
#include <ros/ros.h>
#include "motor.h"
int right_ID1,right_ID2;
int left_ID1,left_ID2;
MOTOR motor;
void speedCallback(const std_msgs::Int16::ConstPtr &msg,int &CAN_ID)//速度模式回调函数
{
ROS_INFO("Set [%d] : speed[%d]", CAN_ID,msg->data);
motor.CAN_VelocityMode((unsigned char)CAN_ID,msg->data);
}
void siteCallback(const std_msgs::Int16::ConstPtr &msg,int &CAN_ID)//位置模式回调函数
{
ROS_DEBUG("Set [%d] : Position[%d]", CAN_ID,msg->data);
motor.CAN_PositionMode((unsigned char)CAN_ID,msg->data);
}
void HaltCallback(const std_msgs::Int16::ConstPtr &msg,,int &CAN_ID){//停止回调函数,没有添加急停是当前方案中没有需要急停的模式
ROS_DEBUG("Set [%d] : Halt!!", CAN_ID);
motor.Halt(CAN_ID);
}
int main(int argc, char *argv[])
{
ros::init(argc, argv, "motor");
bool ENABLESPEED;
ros::NodeHandle private_node_handle("~");
private_node_handle.param<int>("right_ID1",right_ID1,0x01);
private_node_handle.param<int>("right_ID2",right_ID2,0x02);
private_node_handle.param<int>("left_ID1",left_ID1,0x03);
private_node_handle.param<int>("left_ID2",left_ID2,0x04);
private_node_handle.param<bool>("ENABLESPEED",ENABLESPEED,true);
//motor.test();//测试完成20181107
ros::Subscriber sub1,sub2,sub3,sub4,halt1,halt2,halt3,halt4;
motor.CAN_Start();
ros::NodeHandle n;
if(ENABLESPEED){
motor.ENABLEID_speed(right_ID1);
motor.ENABLEID_speed(right_ID2);
motor.ENABLEID_speed(left_ID1);
motor.ENABLEID_speed(left_ID2);
sub1 = n.subscribe<std_msgs::Int16>("right_speed1_ID_"+std::to_string(right_ID1), 1, boost::bind(&speedCallback,_1,right_ID1));
sub2 = n.subscribe<std_msgs::Int16>("right_speed2_ID_"+std::to_string(right_ID2), 1, boost::bind(&speedCallback,_1,right_ID2));
sub3 = n.subscribe<std_msgs::Int16>("left_speed1_ID_"+std::to_string(left_ID1), 1, boost::bind(&speedCallback,_1,left_ID1));
sub4 = n.subscribe<std_msgs::Int16>("left_speed2_ID_"+std::to_string(left_ID2), 1, boost::bind(&speedCallback,_1,left_ID2));
}else{
motor.ENABLEID_position(right_ID1);
motor.ENABLEID_position(right_ID2);
motor.ENABLEID_position(left_ID1);
motor.ENABLEID_position(left_ID2);
sub1 = n.subscribe<std_msgs::Int16>("right_site1_ID_"+std::to_string(right_ID1), 1, boost::bind(&siteCallback,_1,right_ID1));
sub2 = n.subscribe<std_msgs::Int16>("right_site2_ID_"+std::to_string(right_ID2), 1, boost::bind(&siteCallback,_1,right_ID2));
sub3 = n.subscribe<std_msgs::Int16>("left_site1_ID_"+std::to_string(left_ID1), 1, boost::bind(&siteCallback,_1,left_ID1));
sub4 = n.subscribe<std_msgs::Int16>("left_site2_ID_"+std::to_string(left_ID2), 1, boost::bind(&siteCallback,_1,left_ID2));
}
halt1=n.subscribe<std_msgs::Empty>("right_Halt1_ID_"+std::to_string(right_ID1),1, boost::bind(&HaltCallback,_1,right_ID1));
halt2=n.subscribe<std_msgs::Empty>("right_Halt2_ID_"+std::to_string(right_ID2),1, boost::bind(&HaltCallback,_1,right_ID2));
halt3=n.subscribe<std_msgs::Empty>("left_Halt1_ID_"+std::to_string(left_ID1),1, boost::bind(&HaltCallback,_1,left_ID1));
halt4=n.subscribe<std_msgs::Empty>("left_Halt2_ID_"+std::to_string(left_ID1),1, boost::bind(&HaltCallback,_1,left_ID2));
ros::spin();
return 0;
}

2.10 编写launch文件

由于运行BCM2835库需要root权限,因此在launch文件中添加sudo启动支持,ENABLESPEED用于是否开启速度控制模式,1为启用速度模式,0为使用位置控制模式

1
2
3
4
5
6
7
8
9
<launch>
<node pkg="motor_control" type="motor_control_node" name="headbody" required="true" launch-prefix="sudo">
<param name="right_ID1" type="int" value="1"/>
<param name="right_ID2" type="int" value="2"/>
<param name="left_ID1" type="int" value="3"/>
<param name="left_ID2" type="int" value="4"/>
<param name="ENABLESPEED" type="bool" value="0"/>
</node>
</launch>