MoveIt!: Dirty link transformation when planning with joint constraint

asked 2016-02-14 08:03:16 -0600

junhong liang gravatar image

Hello everyone,

today I tried to apply some joint constraints to my robot. Although it did successfully plan out a path, the warning messages "Returning dirty link transforms" keep popping up. I have never encountered such warning messages in other situations, such as planning without constraints and planning with orientation constraints. Am I doing something wrong or I can just safely ignore these warnings?

The following is the console messages I got for planning with joint constraints:

...

[ INFO] [1454419381.859772439]: Planning request received for MoveGroup action. Forwarding to planning pipeline.
[ INFO] [1454419381.862497749]: Planner configuration 'arm[RRTConnectkConfigDefault]' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[ INFO] [1454419381.863397620]: Allocating specialized state sampler for state space
[ INFO] [1454419381.863549883]: arm[RRTConnectkConfigDefault]: Starting planning with 1 states already in datastructure
[ WARN] [1454419381.863729300]: Returning dirty link transforms
[ WARN] [1454419381.864919336]: Returning dirty link transforms
[ WARN] [1454419381.865967656]: Returning dirty link transforms
[ WARN] [1454419381.867010929]: Returning dirty link transforms
[ WARN] [1454419381.867994975]: Returning dirty link transforms
[ WARN] [1454419381.868982175]: Returning dirty link transforms
[ WARN] [1454419381.869976665]: Returning dirty link transforms
[ WARN] [1454419381.870985825]: Returning dirty link transforms
[ WARN] [1454419381.871962708]: Returning dirty link transforms
[ WARN] [1454419381.872938681]: Returning dirty link transforms
[ INFO] [1454419381.878812043]: arm[RRTConnectkConfigDefault]: Created 4 states (2 start + 2 goal)
[ INFO] [1454419381.878908946]: Solution found in 0.016248 seconds
[ INFO] [1454419381.880636688]: SimpleSetup: Path simplification took 0.001372 seconds and changed from 3 to 2 states

...

The following is the code I used:

  // Setting the target pose
  geometry_msgs::Pose target_pose1;
  target_pose1.orientation.x = 1;
  target_pose1.orientation.y = 0;
  target_pose1.orientation.z = 0;
  target_pose1.orientation.w = 0;
  target_pose1.position.x = 0.55;
  target_pose1.position.y = 0.0;
  target_pose1.position.z = 0.3;
  group.setPoseTarget(target_pose1);

  // Setting the start joint positions for all joints to be 0
  std::vector<double> start_joint_positions;
  start_joint_positions.resize(6, 0.0);
  robot_state::RobotState start_state(*group.getCurrentState());
  const robot_state::JointModelGroup *joint_model_group = start_state.getJointModelGroup(group.getName());
  start_state.setJointGroupPositions(joint_model_group, start_joint_positions);
  group.setStartState(start_state);

  // Constructing the joint constraint
  moveit_msgs::JointConstraint jcm;
  jcm.joint_name = "arm_5_joint";
  jcm.position = -1.4;
  jcm.tolerance_above = 1.5;
  jcm.tolerance_below = 1.5;
  jcm.weight = 1.0;

  // Applying the joint constraints
  moveit_msgs::Constraints test_constraints;
  test_constraints.joint_constraints.push_back(jcm); 
  group.setPathConstraints(test_constraints);

  // Start planning
  moveit::planning_interface::MoveGroup::Plan my_plan;
  bool success = false;
  success = group.plan(my_plan);

Any help would be highly appreciated! Thanks in advanced!

Best regards,

Junhong Liang

edit retag flag offensive close merge delete