00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033 #include <ros/ros.h>
00034
00035 #include <sensor_msgs/LaserScan.h>
00036 #include <sensor_msgs/PointCloud.h>
00037 #include <geometry_msgs/PoseStamped.h>
00038 #include <geometry_msgs/Polygon.h>
00039 #include <nav_msgs/Odometry.h>
00040 #include <tf/transform_listener.h>
00041
00042 #include <mrpt/version.h>
00043
00044
00045 #include <mrpt/nav/reactive/CReactiveNavigationSystem.h>
00046 #include <mrpt/maps/CSimplePointsMap.h>
00047 using namespace mrpt::nav;
00048 using mrpt::maps::CSimplePointsMap;
00049
00050 #include <mrpt/utils/CTimeLogger.h>
00051 #include <mrpt/utils/CConfigFileMemory.h>
00052 #include <mrpt/utils/CConfigFile.h>
00053 #include <mrpt/system/filesystem.h>
00054
00055 #include <mrpt_bridge/pose.h>
00056 #include <mrpt_bridge/point_cloud.h>
00057 #include <mrpt_bridge/time.h>
00058
00059 #include <mrpt/kinematics/CVehicleVelCmd_DiffDriven.h>
00060
00061
00062 class ReactiveNav2DNode
00063 {
00064 private:
00065 struct TAuxInitializer
00066 {
00067 TAuxInitializer(int argc, char** argv)
00068 {
00069 ros::init(argc, argv, "mrpt_reactivenav2d");
00070 }
00071 };
00072
00073 mrpt::utils::CTimeLogger m_profiler;
00074 TAuxInitializer m_auxinit;
00075 ros::NodeHandle m_nh;
00076 ros::NodeHandle m_localn;
00077
00080 ros::Subscriber m_sub_nav_goal;
00081 ros::Subscriber m_sub_local_obs;
00082 ros::Subscriber m_sub_robot_shape;
00083 ros::Publisher m_pub_cmd_vel;
00084 tf::TransformListener m_tf_listener;
00085
00087 bool m_1st_time_init;
00088 double m_target_allowed_distance;
00089 double m_nav_period;
00090
00091 std::string m_pub_topic_reactive_nav_goal;
00092 std::string m_sub_topic_local_obstacles;
00093 std::string m_sub_topic_robot_shape;
00094
00095 std::string m_frameid_reference;
00096 std::string m_frameid_robot;
00097
00098 bool m_save_nav_log;
00099
00100 ros::Timer m_timer_run_nav;
00101
00102 CSimplePointsMap m_last_obstacles;
00103 std::mutex m_last_obstacles_cs;
00104
00105 struct MyReactiveInterface :
00106
00107 public mrpt::nav::CRobot2NavInterface
00108 {
00109 ReactiveNav2DNode& m_parent;
00110
00111 MyReactiveInterface(ReactiveNav2DNode& parent) : m_parent(parent) {}
00118 bool getCurrentPoseAndSpeeds(
00119
00120 mrpt::math::TPose2D& curPose, mrpt::math::TTwist2D& curVel,
00121 mrpt::system::TTimeStamp& timestamp,
00122 mrpt::math::TPose2D& curOdometry, std::string& frame_id) override
00123 {
00124 double curV, curW;
00125
00126 mrpt::utils::CTimeLoggerEntry tle(
00127 m_parent.m_profiler, "getCurrentPoseAndSpeeds");
00128 tf::StampedTransform txRobotPose;
00129 try
00130 {
00131 mrpt::utils::CTimeLoggerEntry tle2(
00132 m_parent.m_profiler,
00133 "getCurrentPoseAndSpeeds.lookupTransform_sensor");
00134 m_parent.m_tf_listener.lookupTransform(
00135 m_parent.m_frameid_reference, m_parent.m_frameid_robot,
00136 ros::Time(0), txRobotPose);
00137 }
00138 catch (tf::TransformException& ex)
00139 {
00140 ROS_ERROR("%s", ex.what());
00141 return false;
00142 }
00143
00144 mrpt::poses::CPose3D curRobotPose;
00145 mrpt_bridge::convert(txRobotPose, curRobotPose);
00146
00147 mrpt_bridge::convert(txRobotPose.stamp_, timestamp);
00148 curPose = mrpt::math::TPose2D(
00149 mrpt::poses::CPose2D(curRobotPose));
00150
00151
00152 curOdometry = curPose;
00153
00154 curV = curW = 0;
00155 MRPT_TODO("Retrieve current speeds from odometry");
00156 ROS_DEBUG(
00157 "[getCurrentPoseAndSpeeds] Latest pose: %s",
00158 curPose.asString().c_str());
00159
00160 curVel.vx = curV * cos(curPose.phi);
00161 curVel.vy = curV * sin(curPose.phi);
00162 curVel.omega = curW;
00163
00164 return true;
00165 }
00166
00172 bool changeSpeeds(
00173 const mrpt::kinematics::CVehicleVelCmd& vel_cmd) override
00174 {
00175 using namespace mrpt::kinematics;
00176 const CVehicleVelCmd_DiffDriven* vel_cmd_diff_driven =
00177 dynamic_cast<const CVehicleVelCmd_DiffDriven*>(&vel_cmd);
00178 ASSERT_(vel_cmd_diff_driven);
00179
00180 const double v = vel_cmd_diff_driven->lin_vel;
00181 const double w = vel_cmd_diff_driven->ang_vel;
00182 ROS_DEBUG(
00183 "changeSpeeds: v=%7.4f m/s w=%8.3f deg/s", v,
00184 w * 180.0f / M_PI);
00185 geometry_msgs::Twist cmd;
00186 cmd.linear.x = v;
00187 cmd.angular.z = w;
00188 m_parent.m_pub_cmd_vel.publish(cmd);
00189 return true;
00190 }
00191
00192 bool stop(bool isEmergency) override
00193 {
00194 mrpt::kinematics::CVehicleVelCmd_DiffDriven vel_cmd;
00195 vel_cmd.lin_vel = 0;
00196 vel_cmd.ang_vel = 0;
00197 return changeSpeeds(vel_cmd);
00198 }
00199
00203 virtual bool startWatchdog(float T_ms) override { return true; }
00206 virtual bool stopWatchdog() override { return true; }
00209 bool senseObstacles(
00210 CSimplePointsMap& obstacles,
00211 mrpt::system::TTimeStamp& timestamp) override
00212 {
00213 timestamp = mrpt::system::now();
00214 std::lock_guard<std::mutex> csl(m_parent.m_last_obstacles_cs);
00215 obstacles = m_parent.m_last_obstacles;
00216
00217 MRPT_TODO("TODO: Check age of obstacles!");
00218 return true;
00219 }
00220
00221 mrpt::kinematics::CVehicleVelCmd::Ptr getEmergencyStopCmd() override
00222 {
00223 return getStopCmd();
00224 }
00225 mrpt::kinematics::CVehicleVelCmd::Ptr getStopCmd() override
00226 {
00227 mrpt::kinematics::CVehicleVelCmd::Ptr ret =
00228 mrpt::kinematics::CVehicleVelCmd::Ptr(
00229 new mrpt::kinematics::CVehicleVelCmd_DiffDriven);
00230 ret->setToStop();
00231 return ret;
00232 }
00233
00234 virtual void sendNavigationStartEvent() {}
00235 virtual void sendNavigationEndEvent() {}
00236 virtual void sendNavigationEndDueToErrorEvent() {}
00237 virtual void sendWaySeemsBlockedEvent() {}
00238 };
00239
00240 MyReactiveInterface m_reactive_if;
00241
00242 CReactiveNavigationSystem m_reactive_nav_engine;
00243 std::mutex m_reactive_nav_engine_cs;
00244
00245 public:
00247 ReactiveNav2DNode(int argc, char** argv)
00248 : m_auxinit(argc, argv),
00249 m_nh(),
00250 m_localn("~"),
00251 m_1st_time_init(false),
00252 m_target_allowed_distance(0.40f),
00253 m_nav_period(0.100),
00254 m_pub_topic_reactive_nav_goal("reactive_nav_goal"),
00255 m_sub_topic_local_obstacles("local_map_pointcloud"),
00256 m_sub_topic_robot_shape(""),
00257 m_frameid_reference("/map"),
00258 m_frameid_robot("base_link"),
00259 m_save_nav_log(false),
00260 m_reactive_if(*this),
00261 m_reactive_nav_engine(m_reactive_if)
00262 {
00263
00264 std::string cfg_file_reactive;
00265 m_localn.param(
00266 "cfg_file_reactive", cfg_file_reactive, cfg_file_reactive);
00267 m_localn.param(
00268 "target_allowed_distance", m_target_allowed_distance,
00269 m_target_allowed_distance);
00270 m_localn.param("nav_period", m_nav_period, m_nav_period);
00271 m_localn.param(
00272 "frameid_reference", m_frameid_reference, m_frameid_reference);
00273 m_localn.param("frameid_robot", m_frameid_robot, m_frameid_robot);
00274 m_localn.param(
00275 "topic_robot_shape", m_sub_topic_robot_shape,
00276 m_sub_topic_robot_shape);
00277 m_localn.param("save_nav_log", m_save_nav_log, m_save_nav_log);
00278
00279 ROS_ASSERT(m_nav_period > 0);
00280 ROS_ASSERT_MSG(
00281 !cfg_file_reactive.empty(),
00282 "Mandatory param 'cfg_file_reactive' is missing!");
00283 ROS_ASSERT_MSG(
00284 mrpt::system::fileExists(cfg_file_reactive),
00285 "Config file not found: '%s'", cfg_file_reactive.c_str());
00286
00287 m_reactive_nav_engine.enableLogFile(m_save_nav_log);
00288
00289
00290
00291 try
00292 {
00293 mrpt::utils::CConfigFile cfgFil(cfg_file_reactive);
00294 m_reactive_nav_engine.loadConfigFile(cfgFil);
00295 }
00296 catch (std::exception& e)
00297 {
00298 ROS_ERROR(
00299 "Exception initializing reactive navigation engine:\n%s",
00300 e.what());
00301 throw;
00302 }
00303
00304
00305
00306
00307
00308
00309
00310 if (!m_sub_topic_robot_shape.empty())
00311 {
00312 m_sub_robot_shape = m_nh.subscribe<geometry_msgs::Polygon>(
00313 m_sub_topic_robot_shape, 1,
00314 &ReactiveNav2DNode::onRosSetRobotShape, this);
00315 ROS_INFO(
00316 "Params say robot shape will arrive via topic '%s'... waiting "
00317 "3 seconds for it.",
00318 m_sub_topic_robot_shape.c_str());
00319 ros::Duration(3.0).sleep();
00320 for (size_t i = 0; i < 100; i++) ros::spinOnce();
00321 ROS_INFO("Wait done.");
00322 }
00323
00324
00325
00326 m_pub_cmd_vel = m_nh.advertise<geometry_msgs::Twist>("cmd_vel", 1);
00327
00328
00329
00330
00331
00332 m_sub_nav_goal = m_nh.subscribe<geometry_msgs::PoseStamped>(
00333 m_pub_topic_reactive_nav_goal, 1,
00334 &ReactiveNav2DNode::onRosGoalReceived, this);
00335 m_sub_local_obs = m_nh.subscribe<sensor_msgs::PointCloud>(
00336 m_sub_topic_local_obstacles, 1,
00337 &ReactiveNav2DNode::onRosLocalObstacles, this);
00338
00339
00340
00341 m_timer_run_nav = m_nh.createTimer(
00342 ros::Duration(m_nav_period), &ReactiveNav2DNode::onDoNavigation,
00343 this);
00344
00345 }
00346
00351 void navigateTo(const mrpt::math::TPose2D& target)
00352 {
00353 ROS_INFO(
00354 "[navigateTo] Starting navigation to %s",
00355 target.asString().c_str());
00356
00357 CAbstractPTGBasedReactive::TNavigationParamsPTG navParams;
00358 CAbstractNavigator::TargetInfo target_info;
00359 target_info.target_coords.x = target.x;
00360 target_info.target_coords.y = target.y;
00361 target_info.targetAllowedDistance = m_target_allowed_distance;
00362 target_info.targetIsRelative = false;
00363
00364 navParams.multiple_targets.push_back(target_info);
00365
00366
00367
00368
00369 {
00370 std::lock_guard<std::mutex> csl(m_reactive_nav_engine_cs);
00371 m_reactive_nav_engine.navigate(&navParams);
00372 }
00373 }
00374
00376 void onDoNavigation(const ros::TimerEvent&)
00377 {
00378
00379
00380 if (!m_1st_time_init)
00381 {
00382 m_1st_time_init = true;
00383 ROS_INFO(
00384 "[ReactiveNav2DNode] Initializing reactive navigation "
00385 "engine...");
00386 {
00387 std::lock_guard<std::mutex> csl(m_reactive_nav_engine_cs);
00388 m_reactive_nav_engine.initialize();
00389 }
00390 ROS_INFO(
00391 "[ReactiveNav2DNode] Reactive navigation engine init done!");
00392 }
00393
00394 mrpt::utils::CTimeLoggerEntry tle(m_profiler, "onDoNavigation");
00395
00396 m_reactive_nav_engine.navigationStep();
00397 }
00398
00399 void onRosGoalReceived(const geometry_msgs::PoseStampedConstPtr& trg_ptr)
00400 {
00401 geometry_msgs::PoseStamped trg = *trg_ptr;
00402 ROS_INFO(
00403 "Nav target received via topic sub: (%.03f,%.03f, %.03fdeg) "
00404 "[frame_id=%s]",
00405 trg.pose.position.x, trg.pose.position.y,
00406 trg.pose.orientation.z * 180.0 / M_PI, trg.header.frame_id.c_str());
00407
00408
00409 if (trg.header.frame_id != m_frameid_reference)
00410 {
00411 try
00412 {
00413 geometry_msgs::PoseStamped trg2;
00414 m_tf_listener.transformPose(m_frameid_reference, trg, trg2);
00415 trg = trg2;
00416 }
00417 catch (tf::TransformException& ex)
00418 {
00419 ROS_ERROR("%s", ex.what());
00420 return;
00421 }
00422 }
00423
00424 this->navigateTo(
00425 mrpt::math::TPose2D(
00426 trg.pose.position.x, trg.pose.position.y,
00427 trg.pose.orientation.z));
00428 }
00429
00430 void onRosLocalObstacles(const sensor_msgs::PointCloudConstPtr& obs)
00431 {
00432 std::lock_guard<std::mutex> csl(m_last_obstacles_cs);
00433 mrpt_bridge::point_cloud::ros2mrpt(*obs, m_last_obstacles);
00434
00435
00436 }
00437
00438 void onRosSetRobotShape(const geometry_msgs::PolygonConstPtr& newShape)
00439 {
00440 ROS_INFO_STREAM(
00441 "[onRosSetRobotShape] Robot shape received via topic: "
00442 << *newShape);
00443
00444 mrpt::math::CPolygon poly;
00445 poly.resize(newShape->points.size());
00446 for (size_t i = 0; i < newShape->points.size(); i++)
00447 {
00448 poly[i].x = newShape->points[i].x;
00449 poly[i].y = newShape->points[i].y;
00450 }
00451
00452 {
00453 std::lock_guard<std::mutex> csl(m_reactive_nav_engine_cs);
00454 m_reactive_nav_engine.changeRobotShape(poly);
00455 }
00456 }
00457
00458 };
00459
00460 int main(int argc, char** argv)
00461 {
00462 ReactiveNav2DNode the_node(argc, argv);
00463 ros::spin();
00464 return 0;
00465 }