Go to the documentation of this file.
39 #include <std_msgs/Int8.h>
40 #include <geometry_msgs/TransformStamped.h>
48 static const std::string
LOGNAME =
"cpp_interface_example";
60 void statusCB(
const std_msgs::Int8ConstPtr& msg)
79 int main(
int argc,
char** argv)
88 planning_scene_monitor = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>(
"robot_description");
107 nh.
advertise<geometry_msgs::PoseStamped>(
"target_pose", 1 ,
true );
112 Eigen::Vector3d lin_tol{ 0.01, 0.01, 0.01 };
113 double rot_tol = 0.1;
116 geometry_msgs::TransformStamped current_ee_tf;
120 geometry_msgs::PoseStamped target_pose;
121 target_pose.header.frame_id = current_ee_tf.header.frame_id;
122 target_pose.pose.position.x = current_ee_tf.transform.translation.x;
123 target_pose.pose.position.y = current_ee_tf.transform.translation.y;
124 target_pose.pose.position.z = current_ee_tf.transform.translation.z;
125 target_pose.pose.orientation = current_ee_tf.transform.rotation;
128 target_pose.pose.position.x += 0.1;
136 target_pose_pub.
publish(target_pose);
139 std::thread move_to_pose_thread(
140 [&tracker, &lin_tol, &rot_tol] { tracker.
moveToPose(lin_tol, rot_tol, 0.1 ); });
143 for (
size_t i = 0; i < 500; ++i)
147 target_pose.pose.position.z += 0.0004;
149 target_pose_pub.
publish(target_pose);
156 move_to_pose_thread.join();
int main(int argc, char **argv)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void resetTargetPose()
Re-initialize the target pose to an empty message. Can be used to reset motion between waypoints.
void statusCB(const std_msgs::Int8ConstPtr &msg)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
StatusMonitor(ros::NodeHandle &nh, const std::string &topic)
static const std::string DEFAULT_PLANNING_SCENE_WORLD_TOPIC
#define ROS_ERROR_STREAM_NAMED(name, args)
static const std::string DEFAULT_COLLISION_OBJECT_TOPIC
void stopMotion()
A method for a different thread to stop motion and return early from control loop.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
const std::unordered_map< StatusCode, std::string > SERVO_STATUS_CODE_MAP({ { StatusCode::INVALID, "Invalid" }, { StatusCode::NO_WARNING, "No warnings" }, { StatusCode::DECELERATE_FOR_SINGULARITY, "Close to a singularity, decelerating" }, { StatusCode::HALT_FOR_SINGULARITY, "Very close to a singularity, emergency stop" }, { StatusCode::DECELERATE_FOR_COLLISION, "Close to a collision, decelerating" }, { StatusCode::HALT_FOR_COLLISION, "Collision detected, emergency stop" }, { StatusCode::JOINT_BOUND, "Close to a joint bound (position or velocity), halting" } })
#define ROS_INFO_STREAM_NAMED(name, args)
PoseTrackingStatusCode moveToPose(const Eigen::Vector3d &positional_tolerance, const double angular_tolerance, const double target_pose_timeout)
static const std::string LOGNAME
moveit_servo::StatusCode status_
bool getCommandFrameTransform(geometry_msgs::TransformStamped &transform)
moveit_servo
Author(s): Brian O'Neil, Andy Zelenak
, Blake Anderson, Alexander Rössler , Tyler Weaver
autogenerated on Sat May 3 2025 02:27:56