|
From: <hsu...@us...> - 2009-04-21 23:10:30
|
Revision: 14191
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=14191&view=rev
Author: hsujohnhsu
Date: 2009-04-21 23:10:26 +0000 (Tue, 21 Apr 2009)
Log Message:
-----------
adding return statements. move ROS_ERROR outside of if_timeout.
Modified Paths:
--------------
pkg/trunk/highlevel/nav/src/move_base_action.cpp
pkg/trunk/motion_planning/navfn/src/navfn_ros.cpp
pkg/trunk/world_models/costmap_2d/src/costmap_2d_ros.cpp
Modified: pkg/trunk/highlevel/nav/src/move_base_action.cpp
===================================================================
--- pkg/trunk/highlevel/nav/src/move_base_action.cpp 2009-04-21 22:57:32 UTC (rev 14190)
+++ pkg/trunk/highlevel/nav/src/move_base_action.cpp 2009-04-21 23:10:26 UTC (rev 14191)
@@ -190,13 +190,16 @@
}
catch(tf::LookupException& ex) {
ROS_ERROR("No Transform available Error: %s\n", ex.what());
+ return; // kind of pointless unless there's more code added below this try catch block
}
catch(tf::ConnectivityException& ex) {
ROS_ERROR("Connectivity Error: %s\n", ex.what());
+ return;
}
catch(tf::ExtrapolationException& ex) {
+ ROS_ERROR("Extrapolation Error: %s\n", ex.what());
if (current_time - robot_pose.stamp_ > ros::Duration().fromSec(transform_tolerance_))
- ROS_ERROR("Extrapolation Error: %s\n", ex.what());
+ return;
}
}
Modified: pkg/trunk/motion_planning/navfn/src/navfn_ros.cpp
===================================================================
--- pkg/trunk/motion_planning/navfn/src/navfn_ros.cpp 2009-04-21 22:57:32 UTC (rev 14190)
+++ pkg/trunk/motion_planning/navfn/src/navfn_ros.cpp 2009-04-21 23:10:26 UTC (rev 14191)
@@ -101,11 +101,9 @@
return false;
}
catch(tf::ExtrapolationException& ex) {
+ ROS_ERROR("Extrapolation Error: %s\n", ex.what());
if (current_time - robot_pose.stamp_ > ros::Duration().fromSec(transform_tolerance_))
- {
- ROS_ERROR("Extrapolation Error: %s\n", ex.what());
return false;
- }
}
double wx = global_pose.getOrigin().x();
Modified: pkg/trunk/world_models/costmap_2d/src/costmap_2d_ros.cpp
===================================================================
--- pkg/trunk/world_models/costmap_2d/src/costmap_2d_ros.cpp 2009-04-21 22:57:32 UTC (rev 14190)
+++ pkg/trunk/world_models/costmap_2d/src/costmap_2d_ros.cpp 2009-04-21 23:10:26 UTC (rev 14191)
@@ -346,13 +346,16 @@
}
catch(tf::LookupException& ex) {
ROS_ERROR("No Transform available Error: %s\n", ex.what());
+ return;
}
catch(tf::ConnectivityException& ex) {
ROS_ERROR("Connectivity Error: %s\n", ex.what());
+ return;
}
catch(tf::ExtrapolationException& ex) {
+ ROS_ERROR("Extrapolation Error: %s\n", ex.what());
if (current_time - robot_pose.stamp_ > ros::Duration().fromSec(transform_tolerance_))
- ROS_ERROR("Extrapolation Error: %s\n", ex.what());
+ return;
}
double wx = global_pose.getOrigin().x();
@@ -396,13 +399,16 @@
}
catch(tf::LookupException& ex) {
ROS_ERROR("No Transform available Error: %s\n", ex.what());
+ return;
}
catch(tf::ConnectivityException& ex) {
ROS_ERROR("Connectivity Error: %s\n", ex.what());
+ return;
}
catch(tf::ExtrapolationException& ex) {
+ ROS_ERROR("Extrapolation Error: %s\n", ex.what());
if (current_time - robot_pose.stamp_ > ros::Duration().fromSec(transform_tolerance_))
- ROS_ERROR("Extrapolation Error: %s\n", ex.what());
+ return;
}
double wx = global_pose.getOrigin().x();
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|