Skip to content

Commit

Permalink
Revert change to save_to_warehouse since we don't start the state mon…
Browse files Browse the repository at this point in the history
…itor
  • Loading branch information
JafarAbdi committed Aug 13, 2021
1 parent a92c03c commit 56f718c
Showing 1 changed file with 3 additions and 0 deletions.
3 changes: 3 additions & 0 deletions moveit_ros/warehouse/warehouse/src/save_to_warehouse.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <boost/program_options/parsers.hpp>
#include <boost/program_options/variables_map.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tf2_ros/transform_listener.h>

static const std::string ROBOT_DESCRIPTION = "robot_description";

Expand Down Expand Up @@ -146,6 +147,8 @@ int main(int argc, char** argv)

rclcpp::Clock::SharedPtr clock = std::make_shared<rclcpp::Clock>(RCL_SYSTEM_TIME);
std::shared_ptr<tf2_ros::Buffer> tf_buffer = std::make_shared<tf2_ros::Buffer>(clock);
std::shared_ptr<tf2_ros::TransformListener> tf_listener =
std::make_shared<tf2_ros::TransformListener>(*tf_buffer, node);
planning_scene_monitor::PlanningSceneMonitor psm(node, ROBOT_DESCRIPTION, tf_buffer);
if (!psm.getPlanningScene())
{
Expand Down

0 comments on commit 56f718c

Please sign in to comment.