1- #ifndef SEHER_DEMO_H
2- #define SEHER_DEMO_H
1+ #ifndef MOVEIT_CUSTOM_API_HPP
2+ #define MOVEIT_CUSTOM_API_HPP
3+
34
4- // Includes
55#include " ros/ros.h"
66
77#include < moveit/move_group_interface/move_group_interface.h>
1717#include < moveit_visual_tools/moveit_visual_tools.h>
1818
1919#include < geometry_msgs/PoseStamped.h>
20+ #include < iostream>
2021
2122#include " ur_msgs/SetIO.h"
2223
23- class SeherDemo
24+ class MoveitCustomApi
2425{
2526public:
26- SeherDemo ();
27- SeherDemo (int max_trials, std::string user_prompts);
28- ~SeherDemo ();
27+ MoveitCustomApi ();
28+ MoveitCustomApi (int max_trials, std::string user_prompts);
29+ ~MoveitCustomApi ();
2930
3031 const std::string GROUP_MANIP = " manipulator" ;
3132 const std::string GROUP_GRIPP = " endeffector" ;
@@ -53,7 +54,7 @@ class SeherDemo
5354 bool comparePoses (geometry_msgs::Pose pose1, geometry_msgs::Pose pose2, double delta_posistion=0.05 , double delta_orientation=0.01 );
5455 moveit::planning_interface::MoveGroupInterface::Plan getCartesianPathPlanToPose (geometry_msgs::Pose target_pose, std::string display_label, double eef_step=0.01 , double jump_threshold = 0.0 );
5556 void sleepSafeFor (double duration);
56- void executeCartesianTrajForWaypoints (std::vector<geometry_msgs::Pose> waypoints, double eef, double jump_thresh);
57+ void executeCartesianTrajForWaypoints (std::vector<geometry_msgs::Pose> waypoints, double eef= 0.001 , double jump_thresh = 0.0 );
5758 void executeCartesianTrajtoPose (geometry_msgs::Pose target, std::string label);
5859 void adjustTrajectoryToFixTimeSequencing (moveit_msgs::RobotTrajectory &trajectory);
5960
@@ -75,4 +76,4 @@ class SeherDemo
7576};
7677
7778
78- #endif // SEHER_DEMO_H
79+ #endif // MOVEIT_CUSTOM_API_HPP
0 commit comments