Smallest achievable end effector movement

Hi all,
I am working with a 6 joints robotic arm. In certain situations I need to move the end effector along a very short dinstance, shorter than few hundreds of micrometers. I compute the path through this piece of code:

  PoseStamped pose_goal;
  pose_goal.header.frame_id = "base_link";
  pose_goal.pose = pose;
  // print pose_goal
  if(enable_debug_print) RCLCPP_INFO(get_logger(), "Pose goal:        %f %f %f %f %f %f %f", pose_goal.pose.position.x, pose_goal.pose.position.y, pose_goal.pose.position.z, pose_goal.pose.orientation.x, pose_goal.pose.orientation.y, pose_goal.pose.orientation.z, pose_goal.pose.orientation.w);
  // Add kinematic constraint
  moveit_msgs::msg::Constraints goal;
  goal = kinematic_constraints::constructGoalConstraints(link_name, pose_goal, 50.0E-6, 0.01);
  planning_component->setGoal({goal});
  setupValidRegion(planning_component);

  moveit_cpp::PlanningComponent::PlanRequestParameters single_pipeline_plan_request_params;
  single_pipeline_plan_request_params.planner_id = "PTP";
  single_pipeline_plan_request_params.planning_pipeline = "pilz_industrial_motion_planner";
  single_pipeline_plan_request_params.planning_attempts = 10;
  single_pipeline_plan_request_params.planning_time = 3.0;
  single_pipeline_plan_request_params.max_velocity_scaling_factor = 0.01;
  single_pipeline_plan_request_params.max_acceleration_scaling_factor = 0.01;
  moveit_cpp::PlanningComponent::PlanSolution plan_result = planning_component->plan(single_pipeline_plan_request_params);

even if i specify 50E-6 on the goal constraint I see that if the dinstance is less than about 300 micrometers the resulting trajectory has only one point that it is exaclty the same as the starting state. As a result the robot does not move.

Is there anyone who can explain such behaviour?
Which are the parameters i need to tune to achieve such small movements?

Thanks everyone!

The tolerance specified in constructGoalConstraints just defines the size of the Cartesian region for goal sampling.
There are other tolerances, which affect the planning outcome, e.g. of the IK solver, the planner, or the trajectory filter. The KDL IK solver, for example, uses the ROS parameter epsilon defaulting to 1e-5, to measure the remaining Cartesian error.

This may not be very useful, however, keep in mind that the hardware may not even provide such precise motion. In general, if you wish to move incrementally (using ros2_control), you may consider unloading joint_trajectory_controller for a forward_command_controller. Then command joint position increments based on a Cartesian error. Switch controllers as needed to do path planning again. Let me know if you wish to have a code snippet, something concrete.