Ubuntu18.docx
ROS_Serial_Keil.zip
在Ubuntu 18.04 (bionic) 部署ROS. 主要是测试 intel realsense D435的SLAM性能.
1.
安装 ROS
sudo sh -c '. /etc/lsb-release && echo "deb $DISTRIB_CODENAME main" > /etc/apt/sources.list.d/ros-latest.list'
sudo apt update
sudo apt install ros-melodic-desktop-full
sudo apt install python-rosinstall python-rosinstall-generator python-wstool build-essential
sudo apt-get install -y python-rosdep ninja-build
# apt search ros-melodic 用来查找所有相关的ROS包
sudo rosdep init
rosdep update
部署系统环境
### sudo vi /etc/environment ? ADD
source /opt/ros/melodic/setup.bash
source /work/BIG/Waffle/install_isolated/setup.bash
source /work/BIG/Sensors/install_isolated/setup.bash
export ROS_MASTER_IP=127.0.0.1
export ROS_MASTER_URI={ROS_MASTER_IP}:11311
export ROS_HOSTNAME=127.0.0.1
export GIT_SSL_NO_VERIFY=1
### sudo vi ~/.bashrc ? ADD
source /etc/environment
alias sw='cd /work/BIG/Sensors'
alias ss='cd /work/BIG /Sensors/src'
alias sm='cd /work/BIG/Sensors && catkin_make_isolated --install --use-ninja'
alias gw='cd /work/BIG/Waffle'
alias gs='cd /work/BIG/Waffle/src'
alias gm='cd /work/BIG/Waffle && catkin_make_isolated --install --use-ninja'
2.
创建自己的ROS工作空间.
mkdir –p /work/BIG/Waffle/src;
cd /work/BIG/Waffle
catkin_make_isolated --install --use-ninja
3.
创建ROS程序包
cd /work/BIG/Waffle
catkin_create_pkg big_core std_msgs rospy roscpp
下面自定义 big_core内的文件内容.
4.
单片机支持ROS内容.
sudo apt install ros-melodic-rosserial-client ros-melodic-rosserial
cd /work/BIG/Sensors/src
git clone
修改rosserial_stm32/src/ros_lib/STM32Hardware.h 为自己的STM32Fx系列的头文件. 这个文件在补丁打过之后还要再修改, 主要添加 TIM 以及 串口句柄的设定
修改 rosserial_stm32/src/rosserial_stm32/make_libraries.py
STM32支持 double 类型
'float64' : ('double', 8, PrimitiveDataType, []),
在某个临时目录中, 执行 rosrun rosserial_stm32 make_libraries.py .
处理一下空行和 virtual的问题. 看看 doit.sh的内容.
则在当前目录下产生 Src Inc目录, 把这些目录下的文件放到 Keil的工程中. 先编译过再说.
-
产生的 H 文件一般在 Keil 中编译时会出现问题。主要是
-
1. 文件末尾没有出现空行。
-
for file in `find ./Inc -type f`; do
-
echo "" >> $file;
-
done;
-
-
2. getType/getMD5 需要声明为 virtual, 例如
-
virtual const char * getType(){ return "big_msgs/ChassisBuzzer"; };
-
virtual const char * getMD5(){ return "ab6d0bc19e896bab4d45e3cd705be2f1"; };
-
-
sed -i 's/const char \* getType/virtual const char \* getType/' $file;
-
sed -i 's/const char \* getMD5/virtual const char \* getMD5/' $file;
-
-
3. 一般还要调整
-
-
ROS/node_handle.h 中实际 publisher/subcriber 的实际数量。
-
/* Node Handle */
-
template<class Hardware,
-
int MAX_SUBSCRIBERS = 10,
-
int MAX_PUBLISHERS = 10,
-
int INPUT_SIZE = 512,
-
int OUTPUT_SIZE = 1024> 缓冲区大小也很重要, 否则造成 ROSSerial 失败。
-
-
-
以及 STM32Hardware.h : 主要是因为采用 USB CDC 而 不是物理串口进行通讯的。
-
/*********************************************************************************************************************************/
-
-
#ifndef ROS_STM32_HARDWARE_H_
-
#define ROS_STM32_HARDWARE_H_
-
-
#include <string.h>
-
-
#include "stm32f4xx_hal.h"
-
-
#include "usbd_cdc_if.h"
-
-
extern "C" {
-
void reset_buf_VCPFSRecveived(void);
-
uint16_t read_buf_VCPFSRecveived(void);
-
uint8_t CDC_Transmit_FS(uint8_t* Buf, uint16_t Len);
-
}
-
-
class STM32Hardware {
-
protected:
-
-
public:
-
STM32Hardware() {
-
}
-
-
void init(){
-
reset_rbuf();
-
}
-
-
void reset_rbuf(void){
-
reset_buf_VCPFSRecveived();
-
}
-
-
int read(){
-
int c = -1;
-
uint16_t ch;
-
ch = read_buf_VCPFSRecveived();
-
if (ch != 0xFFFF)
-
c = ch & 0xff;
-
return c;
-
}
-
-
void flush(void){
-
//do nothing.
-
}
-
-
void write(uint8_t* data, int length)
-
{
-
while (CDC_Transmit_FS(data, length) != USBD_OK);
-
}
-
-
unsigned long time()
-
{
-
return HAL_GetTick();
-
}
-
};
-
-
#endif
-
$ cat ROS_Serial_Keil/doit.sh
-
#!/bin/bash
-
-
if [ -d Inc ]; then
-
mkdir Inc
-
fi
-
rm -rf Inc/*
-
-
rosrun rosserial_stm32 make_libraries.py ./
-
-
for file in `find ./Inc -type f`; do
-
echo "" >> $file;
-
sed -i 's/const char \* getType/virtual const char \* getType/' $file;
-
sed -i 's/const char \* getMD5/virtual const char \* getMD5/' $file;
-
done;
-
-
echo "Generate Inc For stm32@keil5 OK."
阅读(5898) | 评论(0) | 转发(0) |