Skip to content

Commit

Permalink
Grab tf2 Buffer from RViz FrameManager
Browse files Browse the repository at this point in the history
  • Loading branch information
IanTheEngineer committed Apr 20, 2018
1 parent 618e530 commit 2da2c8d
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -301,12 +301,8 @@ void MotionPlanningFrame::changePlanningGroupHelper()
opt.node_handle_ = ros::NodeHandle(planning_display_->getMoveGroupNS());
try
{
// FIXME!(imcmahon) this forces the Planning Scene Monitor to allocate a new tf2_ros::Buffer
// and tf2_ros::TransformListener on each invocation. These instances are properly deleted on exit,
// but it would be better to remove the null shared pointer once tf2_ros::Buffer is exposed from
// RViz with something like context_->getFrameManager()->getTFClientPtr()
move_group_.reset(new moveit::planning_interface::MoveGroupInterface(
opt, std::shared_ptr<tf2_ros::Buffer>(), ros::WallDuration(30, 0)));
opt, context_->getFrameManager()->getTFBufferPtr(), ros::WallDuration(30, 0)));
if (planning_scene_storage_)
move_group_->setConstraintsDatabase(ui_->database_host->text().toStdString(), ui_->database_port->value());
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -486,12 +486,8 @@ void PlanningSceneDisplay::unsetLinkColor(rviz::Robot* robot, const std::string&
// ******************************************************************************************
planning_scene_monitor::PlanningSceneMonitorPtr PlanningSceneDisplay::createPlanningSceneMonitor()
{
// FIXME!(imcmahon) this forces the Planning Scene Monitor to allocate a new tf2_ros::Buffer
// and tf2_ros::TransformListener on each invocation. These instances are properly deleted on exit,
// but it would be better to remove the null shared pointer once tf2_ros::Buffer is exposed from
// RViz with something like context_->getFrameManager()->getTFClientPtr()
return planning_scene_monitor::PlanningSceneMonitorPtr(new planning_scene_monitor::PlanningSceneMonitor(
robot_description_property_->getStdString(), std::shared_ptr<tf2_ros::Buffer>(),
robot_description_property_->getStdString(), context_->getFrameManager()->getTFBufferPtr(),
getNameStd() + "_planning_scene_monitor"));
}

Expand Down

0 comments on commit 2da2c8d

Please sign in to comment.