更新文档和注释
parent
b45c54fa34
commit
bcecd984ae
|
@ -1,3 +1,9 @@
|
||||||
|
<!--
|
||||||
|
File Name : UPBot Bringup.launch
|
||||||
|
Review : zhanli.2024.02.28
|
||||||
|
Description : 机器人下位机的启动配置文件,非常重要的基础包,这个包出现配置问
|
||||||
|
题会导致机器人无法工作
|
||||||
|
-->
|
||||||
<launch>
|
<launch>
|
||||||
<arg name="driver_baudrate" default="$(env PIBOT_DRIVER_BAUDRATE)" doc="pibot driver baudrate"/>
|
<arg name="driver_baudrate" default="$(env PIBOT_DRIVER_BAUDRATE)" doc="pibot driver baudrate"/>
|
||||||
<arg name="use_mag" default="false" doc="use mag in pibot imu"/>
|
<arg name="use_mag" default="false" doc="use mag in pibot imu"/>
|
||||||
|
@ -19,7 +25,13 @@
|
||||||
<param name="freq" value="100" />
|
<param name="freq" value="100" />
|
||||||
</node>
|
</node>
|
||||||
|
|
||||||
<!-- PIBOT IMU -->
|
|
||||||
|
<!--
|
||||||
|
pibot_imu : pibot自带的包
|
||||||
|
Review : zhanli.2024.02.28
|
||||||
|
Descripiton : 从源码来看,应该只是负责初始的静态IMU校准工作,会持续订阅原始
|
||||||
|
imu数据并进行imu的零偏校准并发布
|
||||||
|
-->
|
||||||
<node pkg="pibot_imu" type="pibot_imu" name="pibot_imu" output="screen" respawn="false">
|
<node pkg="pibot_imu" type="pibot_imu" name="pibot_imu" output="screen" respawn="false">
|
||||||
<rosparam>
|
<rosparam>
|
||||||
imu/accelerometer_bias: {x: 0.005436, y: 0.014684, z: -0.395418}
|
imu/accelerometer_bias: {x: 0.005436, y: 0.014684, z: -0.395418}
|
||||||
|
@ -61,16 +73,22 @@
|
||||||
<remap from="imu/data" to="imu" />
|
<remap from="imu/data" to="imu" />
|
||||||
</node>
|
</node>
|
||||||
|
|
||||||
|
<!--
|
||||||
|
robot_pose_ekf : ROS提供的一个位姿估计包
|
||||||
|
Review : zhanli.2024.02.08
|
||||||
|
Descripiton : 这个包不在Pibot的中,也不确定当前系统是否有安装?
|
||||||
|
-->
|
||||||
<group ns="/" if="$(arg use_odom)" >
|
<group ns="/" if="$(arg use_odom)" >
|
||||||
<!-- robot pose ekf -->
|
<!-- robot pose ekf -->
|
||||||
<node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen">
|
<node pkg="robot_pose_ekf" type="robot_pose_ekf" name="robot_pose_ekf" output="screen">
|
||||||
<!-- <param name="output_frame" value="odom" /> -->
|
<!-- <param name="output_frame" value="odom" /> -->
|
||||||
<param name="output_frame" value="odom" />
|
<param name="output_frame" value="odom" />
|
||||||
<param name="base_footprint_frame" value="base_link"/>
|
<param name="base_footprint_frame" value="base_link"/>
|
||||||
<param name="freq" value="200.0"/>
|
<param name="freq" value="200.0"/>
|
||||||
<param name="sensor_timeout" value="1.0"/>
|
<param name="sensor_timeout" value="1.0"/>
|
||||||
<param name="odom_used" value="true"/>
|
<param name="odom_used" value="true"/>
|
||||||
<param name="imu_used" value="true"/>
|
<param name="imu_used" value="true"/>
|
||||||
|
<!-- 不使用VSLAM设置为false -->
|
||||||
<param name="vo_used" value="false"/>
|
<param name="vo_used" value="false"/>
|
||||||
<param name="debug" value="false"/>
|
<param name="debug" value="false"/>
|
||||||
<remap from="odom" to="wheel_odom" />
|
<remap from="odom" to="wheel_odom" />
|
||||||
|
|
|
@ -8,19 +8,6 @@
|
||||||
|
|
||||||
Created for the Pi Robot Project: http://www.pirobot.org
|
Created for the Pi Robot Project: http://www.pirobot.org
|
||||||
Copyright (c) 2012 Patrick Goebel. All rights reserved.
|
Copyright (c) 2012 Patrick Goebel. All rights reserved.
|
||||||
|
|
||||||
This program is free software; you can redistribute it and/or modify
|
|
||||||
it under the terms of the GNU General Public License as published by
|
|
||||||
the Free Software Foundation; either version 2 of the License, or
|
|
||||||
(at your option) any later version.5
|
|
||||||
|
|
||||||
This program is distributed in the hope that it will be useful,
|
|
||||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
||||||
GNU General Public License for more details at:
|
|
||||||
|
|
||||||
http://www.gnu.org/licenses/gpl.html
|
|
||||||
|
|
||||||
"""
|
"""
|
||||||
|
|
||||||
import rospy
|
import rospy
|
||||||
|
|
|
@ -114,6 +114,14 @@ void BaseDriver::init_pid_debug()
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**----------------------------------------------------------------------
|
||||||
|
* Function : init_imu
|
||||||
|
* Description : 初始化IMU,创建话题raw_imu,设置50个缓存的队列大小, raw_imu
|
||||||
|
会在pibot_imu里面做校准处理然后发布为imu/data_raw提供给ROS
|
||||||
|
中的其他节点使用
|
||||||
|
* Author : pibot
|
||||||
|
* Review : 2023/04/22 zhanli,Add Description.
|
||||||
|
*---------------------------------------------------------------------**/
|
||||||
void BaseDriver::init_imu()
|
void BaseDriver::init_imu()
|
||||||
{
|
{
|
||||||
raw_imu_pub = nh.advertise<pibot_msgs::RawImu>("raw_imu", 50);
|
raw_imu_pub = nh.advertise<pibot_msgs::RawImu>("raw_imu", 50);
|
||||||
|
|
|
@ -1,5 +1,8 @@
|
||||||
#include "pibot_imu/pibot_imu.h"
|
#include "pibot_imu/pibot_imu.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
// 订阅节点: raw_imu 这个话题是
|
||||||
PibotIMU::PibotIMU(ros::NodeHandle nh, ros::NodeHandle pnh):
|
PibotIMU::PibotIMU(ros::NodeHandle nh, ros::NodeHandle pnh):
|
||||||
// Members default values
|
// Members default values
|
||||||
nh_(nh),
|
nh_(nh),
|
||||||
|
@ -16,9 +19,12 @@ PibotIMU::PibotIMU(ros::NodeHandle nh, ros::NodeHandle pnh):
|
||||||
pnh_.param<bool>("imu/use_magnetometer", use_magnetometer_, use_magnetometer_);
|
pnh_.param<bool>("imu/use_magnetometer", use_magnetometer_, use_magnetometer_);
|
||||||
pnh_.param<bool>("imu/perform_calibration", perform_calibration_, perform_calibration_);
|
pnh_.param<bool>("imu/perform_calibration", perform_calibration_, perform_calibration_);
|
||||||
|
|
||||||
|
// 功能2 :原始IMU的减零偏操作
|
||||||
// 订阅pibot_driver串口读取原始imu数据
|
// 订阅pibot_driver串口读取原始imu数据
|
||||||
|
// 当raw_imu有数据时会调用rawCallback
|
||||||
raw_sub_ = nh_.subscribe("raw_imu", 5, &PibotIMU::rawCallback, this);
|
raw_sub_ = nh_.subscribe("raw_imu", 5, &PibotIMU::rawCallback, this);
|
||||||
|
|
||||||
|
// 功能3 :接收IMU校准服务的校准请求
|
||||||
// 创建一个服务,用于接收运行中的校准请求, 可以rosservice命令查看
|
// 创建一个服务,用于接收运行中的校准请求, 可以rosservice命令查看
|
||||||
imu_cal_srv_ = nh_.advertiseService("imu/calibrate_imu", &PibotIMU::calibrateCallback, this);
|
imu_cal_srv_ = nh_.advertiseService("imu/calibrate_imu", &PibotIMU::calibrateCallback, this);
|
||||||
|
|
||||||
|
@ -95,6 +101,7 @@ void PibotIMU::rawCallback(const pibot_msgs::RawImuConstPtr& raw_msg)
|
||||||
|
|
||||||
static int taken_samples;
|
static int taken_samples;
|
||||||
|
|
||||||
|
// 功能1: 静态零偏校准
|
||||||
if (taken_samples < calibration_samples_) {
|
if (taken_samples < calibration_samples_) {
|
||||||
acceleration_bias_["x"] += raw_msg->raw_linear_acceleration.x;
|
acceleration_bias_["x"] += raw_msg->raw_linear_acceleration.x;
|
||||||
acceleration_bias_["y"] += raw_msg->raw_linear_acceleration.y;
|
acceleration_bias_["y"] += raw_msg->raw_linear_acceleration.y;
|
||||||
|
|
|
@ -1,3 +1,9 @@
|
||||||
|
/*--------------------------------------------------------------
|
||||||
|
* Node Desc : 1.IMU的初始静态零偏校准
|
||||||
|
2.原始IMU的减零偏操作
|
||||||
|
3.接收IMU校准服务的校准请求
|
||||||
|
* Review : zhanli.2024.02.28
|
||||||
|
---------------------------------------------------------------*/
|
||||||
#include "pibot_imu/pibot_imu.h"
|
#include "pibot_imu/pibot_imu.h"
|
||||||
|
|
||||||
int main(int argc, char **argv)
|
int main(int argc, char **argv)
|
||||||
|
|
|
@ -0,0 +1,15 @@
|
||||||
|
# 割草机器人运行指导:
|
||||||
|
|
||||||
|
### 一、全覆盖
|
||||||
|
|
||||||
|
```shell
|
||||||
|
# 进入home目录
|
||||||
|
cd ~
|
||||||
|
# 运行全覆盖server,Server负责路径的规划和小车命令控制
|
||||||
|
./runRoomExplorationServer.sh
|
||||||
|
# 运行全覆盖Client, Client主要负责地图的生成
|
||||||
|
./runRoomExplorationClient.sh
|
||||||
|
# 运行双目摄像头检测节点
|
||||||
|
./runStereo.sh
|
||||||
|
```
|
||||||
|
|
Loading…
Reference in New Issue