43#include <gtest/gtest.h>
48#include <tf2_eigen/tf2_eigen.hpp>
59 const std::string servo_param_namespace =
"moveit_servo_test";
67 FAIL() <<
"Could not retrieve complete robot state";
80 return locked_scene->getCurrentState().getGlobalLinkTransform(target_frame);
Eigen::Isometry3d getCurrentPose(const std::string &target_frame) const
Helper function to get the current pose of a specified frame.
std::shared_ptr< rclcpp::Node > servo_test_node_
std::shared_ptr< const servo::ParamListener > servo_param_listener_
servo::Params servo_params_
std::shared_ptr< moveit_servo::Servo > servo_test_instance_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
planning_scene_monitor::PlanningSceneMonitorPtr createPlanningSceneMonitor(const rclcpp::Node::SharedPtr &node, const servo::Params &servo_params)
Creates the planning scene monitor used by servo.