为什么要利用CMake编译代码并上传到arduino? 当需要开发大点的软件项目,Arduino IDE对代码的管理就变得比较笨拙。 如果你经常想要从命令行或能自动完成的eclipse编译代码 最后你可以通过rosserial_client的CMake基础架构,你利用ROS buildfarm构建和分发固件   这个blog只说一个简单的示例。 老样子,给大家我整理好的包:下载地址   1. 创建工作空间等,此处略 在catkin工作空间下src目录下  
$ cd ~/catkin_ws_cmake/src/
$ catkin_create_pkg helloworld rosserial_arduino rosserial_client std_msgs
  使用catkin_create_pkg创建helloworld包,依赖rosserial_arduino(需要Arduino的工具链)和rosserial_client(客户端库生成macros),最后打算使用std_msgs/String,需要依赖std_msgs。   2. 在helloworld包,建立firmware/chatter.cpp,复制粘贴如下示例代码内容:
#include <ros.h>
#include <std_msgs/String.h>
//Arduino.h头文件,它包含了所有的Arduino函数(digitalRead, analogRead, delay, etc.)
#include <Arduino.h>

ros::NodeHandle nh;

std_msgs::String str_msg;
ros::Publisher chatter("chatter", &str_msg);

char hello[13] = "hello world!";

void setup()
{
  nh.initNode();
  nh.advertise(chatter);
}

void loop()
{
  str_msg.data = hello;
  chatter.publish( &str_msg );
  nh.spinOnce();
  delay(1000);
}
  3. 编辑功能包目录下的CMakeLists.txt文件  
find_package(catkin REQUIRED COMPONENTS
  rosserial_arduino
  rosserial_client
)

catkin_package()

rosserial_generate_ros_lib(
  PACKAGE rosserial_arduino
  SCRIPT make_libraries.py
)

rosserial_configure_client(
  DIRECTORY firmware
  TOOLCHAIN_FILE ${ROSSERIAL_ARDUINO_TOOLCHAIN}
)

rosserial_add_client_target(firmware hello ALL)
rosserial_add_client_target(firmware hello-upload)
  结合rosserial_client的cmake脚本   这里不直接构建固件,而是独立编译Cmake项目,传递目标从catkin包到子项目 rosserial_generate_ros_lib函数创建目标helloworld_ros_lib,它生成rosserial客户端库包含信息头 rosserial_configure_client函数创建一个目标,它会配置CMake项目在特定的子目录,可以使用提供的工具链,在这种情况下,rosserial_arduino提供了有用的Arduino工具链。 最后rosserial_add_client_target调用每个传递过来的目标,因此当我们运行make命令编译 helloworld_firmware_hello的catkin目标,它会配置firmware目录,在其中编译hello目标。   4.在包目录下创建firmware/CMakeLists.txt, 这是需要的第二个CMakeLists.txt,这个是针对固件的子项目,内容如下:  
cmake_minimum_required(VERSION 2.8.3)

include_directories(${ROS_LIB_DIR})

# Remove this if using an Arduino without native USB (eg, other than Leonardo)
add_definitions(-DUSB_CON)

generate_arduino_firmware(hello
  SRCS chatter.cpp ${ROS_LIB_DIR}/time.cpp
  BOARD uno
  PORT /dev/ttyUSB0
)
  generate_arduino_firmware 函数由arduino-cmake toolchain提供它定位Arduino,连接所需的库等BOARD 名称可以在/hardware/arduino/avr/boards.txt找到. 如:   arduino uno 的BOARD名为uno arduino leonardo的BOARD名为leonardo 我这里使用的是uno板   编译  
  1. 固件可以编译默认使用catkin_make,你也可以指定:
catkin_make helloworld_firmware_hello
 
  1. 连接Arduino开发板,确认设备是在/dev/ttyUSB0,或者修改firmware/CMakeLists.txt里面对应的设备号,编译上传:
 
catkin_make helloworld_firmware_hello-upload
  在这里插入图片描述   完成后会有这样一个提示日志  

测试

  分别打开新终端并运行  
roscore
 
rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0
 
rostopic echo chatter
  在这里插入图片描述   道理都是一样的,烧写其他程序也一样