这是一个通过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
13find_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.4编写motor.h头文件
1 |
|
2.5 创建motor_control话题订阅包
- roscreate-pkg motor_control roscpp
2.6 编写CmakeLists.txt文件
1 | cmake_minimum_required(VERSION 2.8.3) |
2.7 编写package.xml文件
1 |
|
2.8 在include文件夹中添加头文件
- 添加bcm2835.h文件
- 添加mcp2515.h文件
- 添加上面motor.h文件
2.9 编写motor_control_node.cpp文件
由于电机拥有四个,将四个定义为right_ID1
、right_ID2
、left_ID1
、left_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
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>