|
From: <is...@us...> - 2009-07-28 06:53:24
|
Revision: 19833
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=19833&view=rev
Author: isucan
Date: 2009-07-28 06:53:08 +0000 (Tue, 28 Jul 2009)
Log Message:
-----------
fix deprecation warnings
Modified Paths:
--------------
pkg/trunk/highlevel/move_arm/src/move_arm_action.cpp
pkg/trunk/motion_planning/ompl_planning/src/helpers/RequestHandler.cpp
pkg/trunk/motion_planning/planning_environment/src/tools/display_planner_collision_model.cpp
Modified: pkg/trunk/highlevel/move_arm/src/move_arm_action.cpp
===================================================================
--- pkg/trunk/highlevel/move_arm/src/move_arm_action.cpp 2009-07-28 06:24:19 UTC (rev 19832)
+++ pkg/trunk/highlevel/move_arm/src/move_arm_action.cpp 2009-07-28 06:53:08 UTC (rev 19833)
@@ -399,7 +399,7 @@
visualization_msgs::Marker mk;
mk.header.stamp = planningMonitor_->lastMapUpdate();
mk.header.frame_id = planningMonitor_->getFrameId();
- mk.ns = node_handle_.getName();
+ mk.ns = ros::this_node::getName();
mk.id = count++;
mk.type = visualization_msgs::Marker::SPHERE;
mk.action = visualization_msgs::Marker::ADD;
@@ -566,7 +566,7 @@
planningMonitor_->getEnvironmentModel()->setVerbose(false);
ros::ServiceClient client = node_handle_.serviceClient<manipulation_srvs::IKService>(ARM_IK_NAME, true);
- for (int t = 0 ; t < 20 ; ++t)
+ for (int t = 0 ; t < 2 ; ++t)
{
robot_msgs::PoseStamped tpose = req.goal_constraints.pose_constraint[0].pose;
if (t > 0)
Modified: pkg/trunk/motion_planning/ompl_planning/src/helpers/RequestHandler.cpp
===================================================================
--- pkg/trunk/motion_planning/ompl_planning/src/helpers/RequestHandler.cpp 2009-07-28 06:24:19 UTC (rev 19832)
+++ pkg/trunk/motion_planning/ompl_planning/src/helpers/RequestHandler.cpp 2009-07-28 06:53:08 UTC (rev 19833)
@@ -476,7 +476,7 @@
visualization_msgs::Marker mk;
mk.header.stamp = psetup->model->planningMonitor->lastMechanismStateUpdate();
mk.header.frame_id = psetup->model->planningMonitor->getFrameId();
- mk.ns = nh_.getName();
+ mk.ns = ros::this_node::getName();
mk.id = 1;
mk.type = visualization_msgs::Marker::POINTS;
mk.action = visualization_msgs::Marker::ADD;
Modified: pkg/trunk/motion_planning/planning_environment/src/tools/display_planner_collision_model.cpp
===================================================================
--- pkg/trunk/motion_planning/planning_environment/src/tools/display_planner_collision_model.cpp 2009-07-28 06:24:19 UTC (rev 19832)
+++ pkg/trunk/motion_planning/planning_environment/src/tools/display_planner_collision_model.cpp 2009-07-28 06:53:08 UTC (rev 19833)
@@ -93,7 +93,7 @@
void objectInMapUpdate(const mapping_msgs::ObjectInMapConstPtr &objectInMap)
{
visualization_msgs::Marker mk;
- mk.ns = nh_.getName() + "_" + objectInMap->id;
+ mk.ns = ros::this_node::getName() + "_" + objectInMap->id;
mk.id = 0;
mk.header = objectInMap->header;
@@ -122,7 +122,7 @@
{
const robot_msgs::Point32 &point = collisionMap->boxes[i].center;
const robot_msgs::Point32 &extents = collisionMap->boxes[i].extents;
- sendPoint(i, nh_.getName(), point.x, point.y, point.z,
+ sendPoint(i, ros::this_node::getName(), point.x, point.y, point.z,
std::max(std::max(extents.x, extents.y), extents.z) * 0.867 + collisionSpaceMonitor_->getPointCloudPadd(),
collisionMap->header);
}
@@ -136,7 +136,7 @@
for (unsigned int i = 0 ; i < link->attachedBodies.size() ; ++i)
{
visualization_msgs::Marker mk;
- mk.ns = nh_.getName() + "_attached_" + link->name;
+ mk.ns = ros::this_node::getName() + "_attached_" + link->name;
mk.id = i;
mk.header = header;
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|