41 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_ros.trajectory_execution_manager.test_app");
43 int main(
int argc,
char** argv)
45 rclcpp::init(argc, argv);
46 auto node = rclcpp::Node::make_shared(
"test_trajectory_execution_manager");
48 auto rml = std::make_shared<robot_model_loader::RobotModelLoader>(node);
54 RCLCPP_ERROR(LOGGER,
"Fail!");
58 RCLCPP_ERROR(LOGGER,
"Fail!");
62 RCLCPP_ERROR(LOGGER,
"Fail!");
66 RCLCPP_ERROR(LOGGER,
"Fail!");
70 RCLCPP_ERROR(LOGGER,
"Fail!");
73 RCLCPP_ERROR(LOGGER,
"Fail!");
78 RCLCPP_ERROR(LOGGER,
"Fail!");
80 moveit_msgs::msg::RobotTrajectory traj1;
81 traj1.joint_trajectory.joint_names.push_back(
"rj1");
82 traj1.joint_trajectory.points.resize(1);
83 traj1.joint_trajectory.points[0].positions.push_back(0.0);
85 RCLCPP_ERROR(LOGGER,
"Fail!");
87 moveit_msgs::msg::RobotTrajectory traj2 = traj1;
88 traj2.joint_trajectory.joint_names.push_back(
"lj2");
89 traj2.joint_trajectory.points[0].positions.push_back(1.0);
90 traj2.multi_dof_joint_trajectory.joint_names.push_back(
"basej");
91 traj2.multi_dof_joint_trajectory.points.resize(1);
92 traj2.multi_dof_joint_trajectory.points[0].transforms.resize(1);
95 RCLCPP_ERROR(LOGGER,
"Fail!");
97 traj1.multi_dof_joint_trajectory = traj2.multi_dof_joint_trajectory;
99 RCLCPP_ERROR(LOGGER,
"Fail!");
102 RCLCPP_ERROR(LOGGER,
"Fail!");
PlanningSceneMonitor Subscribes to the topic planning_scene.
const CurrentStateMonitorPtr & getStateMonitor() const
Get the stored instance of the stored current state monitor.
void execute(const ExecutionCompleteCallback &callback=ExecutionCompleteCallback(), bool auto_clear=true)
Start the execution of pushed trajectories; this does not wait for completion, but calls a callback w...
bool ensureActiveController(const std::string &controller)
Make sure a particular controller is active.
bool push(const moveit_msgs::msg::RobotTrajectory &trajectory, const std::string &controller="")
moveit_controller_manager::ExecutionStatus executeAndWait(bool auto_clear=true)
moveit_controller_manager::ExecutionStatus waitForExecution()
bool ensureActiveControllersForJoints(const std::vector< std::string > &joints)
Make sure the active controllers are such that trajectories that actuate joints in the specified set ...
const rclcpp::Logger LOGGER
int main(int argc, char **argv)