有一次机器人没有装雷达和相机,打算随便跑跑。于是在通用代价地图的障碍层,不设置传感器数据来源,运行move_base
出现频繁报警1
The /scan observation buffer has not been updated for 22.06 seconds, and it should be updated every 5.00 seconds.
来源在1
2
3
4
5
6
7
8
9
10
11
12
13
14bool ObservationBuffer::isCurrent() const
{
if (expected_update_rate_ == ros::Duration(0.0))
return true;
// last_updated_ 没有赋值
bool current = (ros::Time::now() - last_updated_).toSec() <= expected_update_rate_.toSec();
if (!current)
{
ROS_WARN(
"The %s observation buffer has not been updated for %.2f seconds, and it should be updated every %.2f seconds.",
topic_name_.c_str(), (ros::Time::now() - last_updated_).toSec(), expected_update_rate_.toSec());
}
return current;
}
此时发导航命令,又有报警1
[/move_base]:Sensor data is out of date, we're not going to allow commanding of the base for safety
因为没有可靠的传感器数据,move_base
不允许车跑起来。来源在MoveBase::executeCycle
1
2
3
4
5
6if(!controller_costmap_ros_->isCurrent())
{
ROS_WARN("[%s]:Sensor data is out of date, we're not going to allow commanding of the base for safety",ros::this_node::getName().c_str());
publishZeroVelocity();
return false;
}
也就是函数1
2
3
4
5
6
7
8
9bool LayeredCostmap::isCurrent()
{
current_ = true;
for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins_.begin(); plugin != plugins_.end();
++plugin)
{
current_ = current_ && (*plugin)->isCurrent();
}
}
显然是因为障碍层不符合isCurrent
,导致代价地图也不符合isCurrent
。如果希望车照样跑,就把MoveBase::executeCycle
那段注释掉,把ObservationBuffer::isCurrent()
的报警也注释掉,否则没完没了。
从网上下载一个包含雷达数据的bag,又设置了通用代价地图和tf树后,发现报警依然,应该还是时间戳问题,懒得再对齐了。
Packages
, Topics / Services
, 文件、库的命名都采用 under_scored
Classes / Types
的命名采用 CamelCased,比如class ExampleClass
, class HokuyoURGLaser
。 函数命名采用 camelCased,比如int exampleMethod(int example_arg)
普通变量和成员变量命名、命名空间都使用 under_scored,循环中的临时变量使用i,j,k
,i on the outer loop, j on the next inner loop
常量命名采用 ALL_CAPITALS
全局变量采用 g_
开头的 under_scored
每行最多120个字符
所有头文件要包含#ifndef
,比如:
1 |
|
这部分应该在license之后,#endif
在头文件的最后
预处理所用的宏,比如1
2
3
temporary_debugger_break();
函数的输出参数使用指针,而不是引用: int exampleMethod(FooThing input, BarThing* output);
头文件里不要用using namespace
关键字,在源文件里可使用using
,但不要using namespace std;
,而是使用using std::list;
, using std::vector;
,否则引入了std
所有内容。
建议使用Exceptions,而不是returning integer error codes。 析构函数不要抛出异常。 不直接触发的回调函数,不要抛出异常。
保证代码是 exception-safe
: When your code can be interrupted by exceptions, you must ensure that resources you hold will be deallocated when stack variables go out of scope. In particular, mutexes must be released, and heap-allocated memory must be freed. Accomplish this safety by using the following mutex guards and smart pointers
1 | namespace Choices |
This prevents enums from polluting the namespace they’re inside. Individual items within the enum are referenced by: Choices::Choice1, but the typedef still allows declaration of the Choice enum without the namespace.
1 | enum class Choice |
不建议使用全局变量和函数,尤其前者。更不能在多线程中使用。大多数变量和函数都该在类的体内,其他应当在命名空间里。
类不要使用静态变量。
只在 well-defined exit point 调用exit()
函数
使用assertions之类的比条件判断语句好,比如ROS_ASSERT
, ROS_ASSERT_MSG
, ROS_ASSERT_CMD
, ROS_BREADK
Depending on compilation settings, the assertion may not be executed.
It is typical to develop software with assertion-checking enabled, in order to catch violations. When nearing software completion and when assertions are found to always be true in the face of extensive testing, you build with a flag that removes assertions from compilation, so they take up no space or time.
The following option to catkin_make will define the NDEBUG macro for all your ROS packages, and thereby remove assertion checks.catkin_make -DCMAKE_CXX_FLAGS:STRING="-DNDEBUG"
Note: cmake will rebuild all your software when you run it with this command, and will remember the setting through subsequent catkin_make runs until you delete your build and devel directories and rebuild.
1 |
|
cmake 中判断CPU 架构,操作系统类型1
2
3
4
5
6
7
8
9
10
11
12
13
14
15cmake_minimum_required(VERSION 3.10.0)
message(${CMAKE_HOST_SYSTEM_NAME})
message(${CMAKE_HOST_SYSTEM_PROCESSOR})
if(CMAKE_HOST_SYSTEM_NAME MATCHES "Linux")
message("this is Linux")
elseif(CMAKE_HOST_SYSTEM_NAME MATCHES "Windows")
message("this is Windows")
endif()
if(CMAKE_HOST_SYSTEM_PROCESSOR MATCHES "aarch64")
message("this is aarch64 cpu")
elseif(CMAKE_HOST_SYSTEM_PROCESSOR MATCHES "x86_64")
message("this is x86_64 cpu")
endif()
根据编译器的情况,有下面的宏用于调试程序:1
2
3
4
5
6
7
8
9
10
11
12
13
14
15//判断是不是C++环境,需要注意的是ROS环境中这里为否
printf("C++\n");
//判断是不是C环境
printf("C\n");
//输出语句所在函数,行,文件等参数
printf("function %s: Line 25\n",__func__); //或者用__FUNCTION__
printf("pretty function %s: Line 25\n",__PRETTY_FUNCTION__); //函数声明,包括了参数
printf("line: %d\n",__LINE__);
printf("current file: %s\n",__FILE__);
printf("date: %s\n",__DATE__);
printf("time: %s\n",__TIME__);
源码其实并不复杂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
37bool Costmap2DROS::getRobotPose(tf::Stamped<tf::Pose>& global_pose) const
{
global_pose.setIdentity();
tf::Stamped < tf::Pose > robot_pose;
robot_pose.setIdentity();
robot_pose.frame_id_ = robot_base_frame_;
robot_pose.stamp_ = ros::Time();
ros::Time current_time = ros::Time::now(); // save time for checking tf delay later
try
{
tf_.transformPose(global_frame_, robot_pose, global_pose);
}
catch (tf::LookupException& ex)
{
ROS_ERROR_THROTTLE(1.0, "No Transform available Error looking up robot pose: %s\n", ex.what());
return false;
}
catch (tf::ConnectivityException& ex)
{
ROS_ERROR_THROTTLE(1.0, "Connectivity Error looking up robot pose: %s\n", ex.what());
return false;
}
catch (tf::ExtrapolationException& ex)
{
ROS_ERROR_THROTTLE(1.0, "Extrapolation Error looking up robot pose: %s\n", ex.what());
return false;
}
// check global_pose timeout
if (current_time.toSec() - global_pose.stamp_.toSec() > transform_tolerance_)
{
ROS_WARN_THROTTLE(1.0,
"Costmap2DROS transform timeout. Current time: %.4f, global_pose stamp: %.4f, tolerance: %.4f",
current_time.toSec(), global_pose.stamp_.toSec(), transform_tolerance_);
return false;
}
return true;
}
核心是函数 transformPose
,tf_
在这里是tf::TransformListener
,但函数实际是继承自基类tf::Transformer
,有两个重载,常用的是第一个1
2
3
4
5
6
7
8
9
10
11void Transformer::transformPose(const std::string& target_frame,
const Stamped< tf::Pose >& stamped_in,
Stamped< tf::Pose >& stamped_out
) const
void Transformer::transformPose(const std::string& target_frame,
const ros::Time& target_time,
const Stamped< tf::Pose >& stamped_in,
const std::string& fixed_frame,
Stamped< tf::Pose >& stamped_out
) const
第二个重载会调用函数lookupTransform
1
2
3
4
5
6
7
8// Get the transform between two frames by frame ID assuming fixed frame.
void Transformer::lookupTransform ( const std::string & target_frame,
const ros::Time & target_time,
const std::string & source_frame,
const ros::Time & source_time,
const std::string & fixed_frame,
StampedTransform & transform
) const
可能抛出的异常1
2
3
4
5
6
7
8namespace tf{
// Pass through exceptions from tf2
typedef tf2::TransformException TransformException;
typedef tf2::LookupException LookupException;
typedef tf2::ConnectivityException ConnectivityException;
typedef tf2::ExtrapolationException ExtrapolationException;
typedef tf2::InvalidArgumentException InvalidArgument;
}
报警对应的transform_tolerance_
是在构造函数里写死的0.3
,一开始我以为这个数太小了,于是改为2,结果没有改善。
以下报警的根源都是Costmap2DROS::getRobotPose
尝试的改善措施(全都无效):
Costmap2DROS
构造函数中设置: transform_tolerance_(2)
timer_ = private_nh.createTimer(ros::Duration(.1), &Costmap2DROS::movementCB, this);
0.1秒间隔太短了。增大到1.5,稍有改善,但未解决根本问题,反而降低了代价地图的性能。update_frequency
所有报警基本来自Costmap2DROS::getRobotPose
,或者说map
—->base_link
的tf变换不及时。
xv_sdk.launch
,使用static_transform_republisher
建立假的TF树,启动导航框架,一个报警也没有。因此问题还在VSLAM,怀疑是CPU而不是网络问题。xv_sdk.launch
和VSLAM,但不发布tf,使用假的tf树,启动导航框架,仍然没有报警。world
—->map
—->odom
—-> base_link
,导航框架不报警。但是如果由VSLAM发布map
—->odom
,就有报警了。所以问题的原因:
map
—->odom
—-> base_link
变换。在此情况下规划路径时,全局路径可生成,因为全局规划频率是0,虽然有很多报警,总能成功规划一次。但局部路径就不同了,需要频繁规划。
只看TF的频率和tf echo
有没有数据还不够,应该看Rviz里,base_link
坐标系在map
中的坐标是否能随着机器人的移动实时更新。先满足这一点,再运行导航框架。
unique_lock
是管理具有唯一所有权的互斥对象的对象。类似智能指针unique_ptr
。在构造时(或通过移动分配给它),对象获得一个互斥对象,负责该对象的锁定和解锁操作。该对象支持两种状态:锁定和解锁。此类保证在销毁时将管理的互斥对象解锁(即使未显式调用解锁函数)。因此,它能够保证互斥对象在抛出异常的情况下正确解锁,克服了mutex使用中的缺点。但是,unique_lock对象不以任何方式管理互斥对象的生命周期:这要求互斥对象的持续时间应至少延长到管理它的unique_lock销毁。
unique_lock
是一个模板类,需要使用Mutex类型作为模板参数。
try_lock
初始化: 新创建的unique_lock
对象管理Mutex
对象m
,并尝试调用m.lock()
对Mutex
对象进行上锁,如果此时另外某个unique_lock
对象已经管理了该Mutex
对象m
,则当前线程将会被阻塞。
try-locking
初始化: 新创建的unique_lock
对象管理Mutex对象m,并尝试调用m.try_lock()对Mutex对象进行上锁,但如果上锁不成功,并不会阻塞当前线程
1 | boost::mutex mut; |
如果一个mutex
被许多模块和类共享,就使用boost::recursive_mutex
,如果只被一个模块和类使用,而且不需要re-entrant特性, 就使用boost::mutex
特点:
1 |
|
这种情况下,线程正常运行,不会死锁。
但是这种情况下,线程就死锁了,只能运行foo
,因为mutex不可重入,foo
这个线程没有运行完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
using namespace std;
boost::mutex mtx;
void bar()
{
boost::mutex::scoped_lock lLock(mtx); // dead-locked here
std::cout << "bar" << std::endl;
}
void foo()
{
boost::mutex::scoped_lock lLock(mtx);
std::cout << "foo" << std::endl;
bar();
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "test_curve");
ros::NodeHandle n;
foo();
return 0;
}
如果把mutex
换成recursive_mutex
,又能正常运行了。
recursive_mutex类可多次进入锁,这样在递归时可以避免一次死锁的几率,这是原本BOOST中所体现的一种思想。递归锁可多次锁,同样的需要多次解锁,那么问题就来了,如果真正或可能造成这次死锁的位置在某个已经进入死锁的地方,那么死锁的位置可能并不是你需要的位置,简单的说,如果A锁了3次,B锁一次,C锁一次,这样就锁出现死锁,排错之困难可想而知。
1 |
|
thread_1
里如果lock
3次,unlock
1次,运行时会阻塞在thread_1
。只有3次unlock
才会正常运行两个线程。
头文件1
2
3
4
5
6
open
函数默认是读模式。
写bag文件:1
2
3
4
5
6
7
8
9
10rosbag::Bag bag;
try{
bag.open("/home/user/plan.bag", rosbag::bagmode::Write);
}
catch (const rosbag::BagException& ex) {
ROS_ERROR("open rosbag error: %s", ex.what() );
return;
}
bag.write("record_plan",ros::Time::now(), coverage_plan);
bag.close();
打开文件的模式有:enum rosbag::bagmode::BagMode
1
2
3Write
Read
Append
读bag文件一定要用try
和catch
下面的例子,bag文件只有一个话题/move_base/transformed_plan
,一堆nav_msgs/Path
消息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
30rosbag::Bag bag;
try{
bag.open("/home/user/plan.bag", rosbag::bagmode::Read);
}
catch (const rosbag::BagException& ex) {
ROS_ERROR("open rosbag error: %s", ex.what() );
return;
}
std::vector<std::string> topics;
bool bag_read_once = false;
topics.push_back(std::string("record_plan") );
rosbag::View view(bag, rosbag::TopicQuery(topics) );
BOOST_FOREACH(rosbag::MessageInstance const m, view)
{
nav_msgs::Path::ConstPtr i = m.instantiate<nav_msgs::Path>();
plan_from_bag.header.frame_id = i->header.frame_id;
plan_from_bag.header.stamp = i->header.stamp;
plan_from_bag.header.seq = i->header.seq;
unsigned int path_size = i->poses.size();
ROS_INFO("plan from bag size: %zu",i->poses.size() );
plan_from_bag.poses.reserve(path_size);
if(bag_read_once) break;
plan_from_bag.poses = i->poses;
bag_read_once = true;
}
bag.close();
注意读的时候,topics容器的元素必须还是number
,与写文件时一致。如果不一致,读文件会不执行foreach
用到的类如下:1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21/* Create a view and add a query
* param bag The bag file on which to run this query
* param query The actual query to evaluate which connections to include
* param start_time The beginning of the time range for the query
* param end_time The end of the time range for the query
* param reduce_overlap If multiple views return the same messages, reduce them to a single message
*/
View(Bag const& bag, boost::function<bool(ConnectionInfo const*)> query,
ros::Time const& start_time = ros::TIME_MIN, ros::Time const& end_time = ros::TIME_MAX, bool const& reduce_overlap = false);
class ROSBAG_DECL TopicQuery
{
public:
TopicQuery(std::string const& topic);
TopicQuery(std::vector<std::string> const& topics);
bool operator()(ConnectionInfo const*) const;
private:
std::vector<std::string> topics_;
};
rosbag::View
的常用函数
iterator begin()
Simply copy the merge_queue state into the iterator.iterator end()
Default constructed iterator signifies end.ros::Time getBeginTime()
ros::Time getEndTime()
uint32_t size ()
获得bag文件中所含消息的个数,不是文件大小其他常用函数1
2
3
4
5
6
7// Get the filename of the bag
std::string getFileName () const
// Get the current size of the bag file (a lower bound) More...
uint64_t getSize () const
bool isOpen () const
这种情况下如果没有用try
和catch
就会出错
我查来查去,没发现C++ API里有类似rosbag reindex
命令的函数,只能不处理。似乎python里有,没有深入研究,
参考:
rosbag API
Costmap2DROS
类是2D Costmap
的ROS封装类,处理订阅的话题,这些话题提供了对障碍物的观测,方式为点云或激光扫描消息。 costmap_2d::Costmap2DROS
给用户提供了纯2D的接口,这意味着查询障碍只能在列上进行。例如,在XY平面上位于同一位置的桌子和鞋,虽然在Z方向上有差异但是它们在costmap_2d::Costmap2DROS
对象代价地图中对应的cell上拥有相同的代价值。
A ROS wrapper for a 2D Costmap. Handles subscribing to topics that provide observations about obstacles in either the form of PointCloud or LaserScan messages.
实际是return layered_costmap_->getCostmap();
,跟getLayeredCostmap()->getCostmap()
一样. Return a pointer to the “master” costmap which receives updates from all the layers.1
costmap_2d::Costmap2D* global_costmap = planner_costmap_ros_->getCostmap();
获取机器人在代价地图的global frame
中的位姿,成功获取则返回true1
2
3
4
5
6
7
8
9
10
11// 这个返回类型很不方便
tf::Stamped<tf::Pose> pose;
if(!costmap->getRobotPose(pose))
{
ROS_ERROR("Cannot clear map because pose cannot be retrieved");
return;
}
double x = pose.getOrigin().x();
double y = pose.getOrigin().y();
double yaw = tf::getYaw(pose.getRotation());
double yaw_norm = angles::normalize_angle(tf::getYaw(pose.getRotation() ) );
对于全局代价地图,一般是返回在map
坐标系下的位姿,对于局部代价地图,一般是在odom
或者map
下的位姿。
Costmap2DROS::getRobotPose函数调用分析
这两个返回的就是代价地图yaml里配置的全局和局部坐标系
LayeredCostmap* getLayeredCostmap()
std::vector<geometry_msgs::Point> getRobotFootprint()
获取机器人边界(在机器人坐标系下,包含padding),返回的是vector<geometry_msgs::Point>
,索引顺序就是yaml中设置的顺序
std::vector<geometry_msgs::Point>getUnpaddedRobotFootprint()
获取机器人边界(在机器人坐标系下,不包含padding)
geometry_msgs::Polygon getRobotFootprintPolygon()
获取机器人边界(在机器人坐标系下,包含padding)