moveit_servoing not working when removing target_pose.pose.position.x
Hi, I am using pose_tracking_example.cpp. When I am removing line 128, that is the change in x little bit. then the program runs but the robot doesn't move at all.
// Modify it a little bit
target_pose.pose.position.x += 0.1;
I am not sure why this is happening. Any suggestion would be appreciated
CODE
#include <std_msgs/Int8.h>
#include <geometry_msgs/TransformStamped.h>
#include <moveit_servo/servo.h>
#include <moveit_servo/pose_tracking.h>
#include <moveit_servo/status_codes.h>
#include <moveit_servo/make_shared_from_pool.h>
#include <thread>
static const std::string LOGNAME = "cpp_interface_example";
// Class for monitoring status of moveit_servo
class StatusMonitor
{
public:
StatusMonitor(ros::NodeHandle& nh, const std::string& topic)
{
sub_ = nh.subscribe(topic, 1, &StatusMonitor::statusCB, this);
}
private:
void statusCB(const std_msgs::Int8ConstPtr& msg)
{
moveit_servo::StatusCode latest_status = static_cast<moveit_servo::StatusCode>(msg->data);
if (latest_status != status_)
{
status_ = latest_status;
const auto& status_str = moveit_servo::SERVO_STATUS_CODE_MAP.at(status_);
ROS_INFO_STREAM_NAMED(LOGNAME, "Servo status: " << status_str);
}
}
moveit_servo::StatusCode status_ = moveit_servo::StatusCode::INVALID;
ros::Subscriber sub_;
};
/**
* Instantiate the pose tracking interface.
* Send a pose slightly different from the starting pose
* Then keep updating the target pose a little bit
*/
int main(int argc, char** argv)
{
ros::init(argc, argv, LOGNAME);
ros::NodeHandle nh("~");
ros::AsyncSpinner spinner(8);
spinner.start();
// Load the planning scene monitor
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor;
planning_scene_monitor = std::make_shared<planning_scene_monitor::PlanningSceneMonitor>("robot_description");
if (!planning_scene_monitor->getPlanningScene())
{
ROS_ERROR_STREAM_NAMED(LOGNAME, "Error in setting up the PlanningSceneMonitor.");
exit(EXIT_FAILURE);
}
planning_scene_monitor->startSceneMonitor();
planning_scene_monitor->startWorldGeometryMonitor(
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_COLLISION_OBJECT_TOPIC,
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_WORLD_TOPIC,
false /* skip octomap monitor */);
planning_scene_monitor->startStateMonitor();
// Create the pose tracker
moveit_servo::PoseTracking tracker(nh, planning_scene_monitor);
// Make a publisher for sending pose commands
ros::Publisher target_pose_pub =
nh.advertise<geometry_msgs::PoseStamped>("target_pose", 1 /* queue */, true /* latch */);
// Subscribe to servo status (and log it when it changes)
StatusMonitor status_monitor(nh, "status");
Eigen::Vector3d lin_tol{ 0.01, 0.01, 0.01 };
double rot_tol = 0.1;
// Get the current EE transform
geometry_msgs::TransformStamped current_ee_tf;
tracker.getCommandFrameTransform(current_ee_tf);
// Convert it to a Pose
geometry_msgs::PoseStamped target_pose;
target_pose.header.frame_id = current_ee_tf.header.frame_id;
target_pose.pose.position.x = current_ee_tf.transform.translation.x;
target_pose.pose.position.y = current_ee_tf.transform.translation.y;
target_pose.pose.position.z = current_ee_tf.transform.translation.z;
target_pose.pose.orientation = current_ee_tf.transform.rotation;
// Modify it a little bit
target_pose.pose.position.x += 0.1;
// resetTargetPose() can be used to clear the target pose and wait for a new one, e.g. when moving between multiple
// waypoints
tracker.resetTargetPose();
// Publish target pose
target_pose.header.stamp = ros::Time::now();
target_pose_pub.publish(target_pose);
// Run the pose tracking in a new thread
std::thread move_to_pose_thread(
[&tracker, &lin_tol, &rot_tol] { tracker.moveToPose(lin_tol, rot_tol, 0.1 /* target pose timeout */); });
ros::Rate loop_rate(50);
for (size_t i = 0; i < 500; ++i)
{
// Modify the pose target a little bit each cycle
// This is a dynamic pose target
target_pose.pose.position.z += 0.0004;
target_pose.header.stamp = ros::Time::now();
target_pose_pub.publish(target_pose);
loop_rate.sleep();
}
// Make sure the tracker is stopped and clean up
tracker.stopMotion();
move_to_pose_thread.join();
return EXIT_SUCCESS;
}
duplicate #q412827
@Ranjit this is not the duplicate question, it's asking about different thing than what is being asked on another question. Please read the question carefully before marking it as duplicate.