tf教程(四):Adding a frame

本教程介绍如何在ROS中使用tf包为系统中的传感器或链接定义局部坐标系,并通过示例展示如何向tf树中添加额外的坐标系。

Adding a frame (C++)

Description:  This tutorial teaches you how to add an extra fixed frame to tf.

Tutorial Level:  BEGINNER

Next Tutorial:  tf and time  (C++)  

In the previous tutorials we recreated the turtle demo by adding a tf broadcaster and a tf listener. This tutorial will teach you how to add an extra frame to the tf tree. This is very similar to creating the tf broadcaster, and will show some of the power of tf.

Why adding frames

For many tasks it is easier to think inside a local frame, e.g. it is easier to reason about a laser scan in a frame at the center of the laser scanner. tf allows you to define a local frame for each sensor, link, etc in your system. And, tf will take care of all the extra frame transforms that are introduced.

Where to add frames

tf builds up a tree structure of frames; it does not allow a closed loop in the frame structure. This means that a frame only has one single parent, but it can have multiple children. Currently our tf tree contains three frames: world, turtle1 and turtle2. The two turtles are children of world. If we want to add a new frame to tf, one of the three existing frames needs to be the parent frame, and the new frame will become a child frame.

  • tree.png

How to add a frame

In our turtle example, we'll add a new frame to the first turtle. This frame will be the "carrot" for the second turtle.

Let's first create the source files. Go to the package we created for the previous tutorials:

 $ roscd learning_tf

The Code

Fire up your favorite editor and paste the following code into a new file called src/frame_tf_broadcaster.cpp.

切换行号显示
#include <ros/ros.h>
#include <tf/transform_broadcaster.h>

int main(int argc, char** argv){
  ros::init(argc, argv, "my_tf_broadcaster");
  ros::NodeHandle node;

  tf::TransformBroadcaster br;
  tf::Transform transform;

  ros::Rate rate(10.0);
  while (node.ok()){
    transform.setOrigin( tf::Vector3(0.0, 2.0, 0.0) );
    transform.setRotation( tf::Quaternion(0, 0, 0, 1) );
    br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "turtle1", "carrot1"));
    rate.sleep();
  }
  return 0;
};

The code is very similar to the example in the tf broadcaster tutorial.

The Code Explained

Let's take a look at the key line in this piece of code:

切换行号显示
  13     transform.setOrigin( tf::Vector3(0.0, 2.0, 0.0) );
  14     transform.setRotation( tf::Quaternion(0, 0, 0, 1) );
  15     br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "turtle1", "carrot1"));

Here we create a new transform, from the parent turtle1 to the new child carrot1. The carrot1 frame is 2 meters offset to the left from the turtle1 frame.

Running the frame broadcaster

Now that we created the code, lets compile it first. Open the CMakeLists.txt file, and add the following line on the bottom:

add_executable(frame_tf_broadcaster src/frame_tf_broadcaster.cpp)
target_link_libraries(frame_tf_broadcaster ${catkin_LIBRARIES})

Build your package at the top folder of your catkin workspace:

 $ catkin_make

If everything went well, you should have a binary file called frame_tf_broadcaster in your bin folder. If so, we're ready to edit the start_demo.launch launch file. Simply merge the node block below inside the launch block::

  <launch>
    ...
    <node pkg="learning_tf" type="frame_tf_broadcaster"
          name="broadcaster_frame" />
  </launch>

First, make sure you stopped the launch file from the previous tutorial (use Ctrl-c). Now you're ready to start the turtle broadcaster demo:

 $ roslaunch learning_tf start_demo.launch

Checking the results

So, if you drive the first turtle around, you notice that the behavior didn't change from the previous tutorial, even though we added a new frame. That's because adding an extra frame does not affect the other frames, and our listener is still using the previously defined frames. So, let's change the behavior of the listener.

Open the src/turtle_tf_listener.cpp file, and simple replace "/turtle1" with "/carrot1" in lines 26-27:

切换行号显示
   1   listener.lookupTransform("/turtle2", "/carrot1",
   2                            ros::Time(0), transform);

And now the good part: just rebuild and restart the turtle demo, and you'll see the second turtle following the carrot instead of the first turtle! Remember that the carrot is 2 meters to the left of turtle1. There is no visual representation for the carrot, but you should see the second turtle moving to that point.

 $ catkin_make
 $ roslaunch learning_tf start_demo.launch

Broadcasting a moving frame

The extra frame we published in this tutorial is a fixed frame that doesn't change over time in relation to the parent frame. However, if you want to publish a moving frame you can change the broadcaster to change over time. Let's modify the /carrot1 frame to change relative to /turtle1 over time.

切换行号显示
   1     transform.setOrigin( tf::Vector3(2.0*sin(ros::Time::now().toSec()), 2.0*cos(ros::Time::now().toSec()), 0.0) );
   2     transform.setRotation( tf::Quaternion(0, 0, 0, 1) );

And now the good part: just rebuild and restart the turtle demo, and you'll see the second turtle following a moving carrot.

 $ catkin_make
 $ roslaunch learning_tf start_demo.launch

You're now ready to move to the next tutorial about tf and time (Python) (C++)

[ WARN] [1762076634.614271498]: Skipping virtual joint 'base_link' because its child frame 'base_link' does not match the URDF frame 'world' [ INFO] [1762076634.614330146]: No root/virtual joint specified in SRDF. Assuming fixed joint [ INFO] [1762076635.805948068]: Ready to take commands for planning group manipulator_i5. [INFO] [1762076635.806458]: AUBO安全控制器初始化完成 [INFO] [1762076635.813104]: 使用保守参数: 速度=0.1, 加速度=0.1 roslaunch aubo_i5_moveit_config moveit_planning_execution.launch sim:=false robot_ip:=192.168.192.10 ... logging to /root/.ros/log/69be2d1c-b7d0-11f0-a111-2c9464039e34/roslaunch-tian-28357.log Checking log directory for disk usage. This may take a while. Press Ctrl-C to interrupt Done checking log file disk usage. Usage is <1GB. xacro: in-order processing became default in ROS Melodic. You can drop the option. started roslaunch server http://tian:34027/ SUMMARY ======== PARAMETERS * /aubo_driver/server_host: 192.168.192.10 * /controller_joint_names: ['shoulder_joint'... * /move_group/allow_trajectory_execution: True * /move_group/capabilities: * /move_group/controller_list: [{'default': True... * /move_group/disable_capabilities: * /move_group/jiggle_fraction: 0.05 * /move_group/manipulator_i5/default_planner_config: RRTConnect * /move_group/manipulator_i5/longest_valid_segment_fraction: 0.005 * /move_group/manipulator_i5/planner_configs: ['SBL', 'EST', 'L... * /move_group/manipulator_i5/projection_evaluator: joints(shoulder_j... * /move_group/max_range: 5.0 * /move_group/max_safe_path_cost: 1 * /move_group/moveit_controller_manager: moveit_simple_con... * /move_group/moveit_manage_controllers: True * /move_group/octomap_resolution: 0.025 * /move_group/planner_configs/BFMT/balanced: 0 * /move_group/planner_configs/BFMT/cache_cc: 1 * /move_group/planner_configs/BFMT/extended_fmt: 1 * /move_group/planner_configs/BFMT/heuristics: 1 * /move_group/planner_configs/BFMT/nearest_k: 1 * /move_group/planner_configs/BFMT/num_samples: 1000 * /move_group/planner_configs/BFMT/optimality: 1 * /move_group/planner_configs/BFMT/radius_multiplier: 1.0 * /move_group/planner_configs/BFMT/type: geometric::BFMT * /move_group/planner_configs/BKPIECE/border_fraction: 0.9 * /move_group/planner_configs/BKPIECE/failed_expansion_score_factor: 0.5 * /move_group/planner_configs/BKPIECE/min_valid_path_fraction: 0.5 * /move_group/planner_configs/BKPIECE/range: 0.0 * /move_group/planner_configs/BKPIECE/type: geometric::BKPIECE * /move_group/planner_configs/BiEST/range: 0.0 * /move_group/planner_configs/BiEST/type: geometric::BiEST * /move_group/planner_configs/BiTRRT/cost_threshold: 1e300 * /move_group/planner_configs/BiTRRT/frountier_node_ratio: 0.1 * /move_group/planner_configs/BiTRRT/frountier_threshold: 0.0 * /move_group/planner_configs/BiTRRT/init_temperature: 100 * /move_group/planner_configs/BiTRRT/range: 0.0 * /move_group/planner_configs/BiTRRT/temp_change_factor: 0.1 * /move_group/planner_configs/BiTRRT/type: geometric::BiTRRT * /move_group/planner_configs/EST/goal_bias: 0.05 * /move_group/planner_configs/EST/range: 0.0 * /move_group/planner_configs/EST/type: geometric::EST * /move_group/planner_configs/FMT/cache_cc: 1 * /move_group/planner_configs/FMT/extended_fmt: 1 * /move_group/planner_configs/FMT/heuristics: 0 * /move_group/planner_configs/FMT/nearest_k: 1 * /move_group/planner_configs/FMT/num_samples: 1000 * /move_group/planner_configs/FMT/radius_multiplier: 1.1 * /move_group/planner_configs/FMT/type: geometric::FMT * /move_group/planner_configs/KPIECE/border_fraction: 0.9 * /move_group/planner_configs/KPIECE/failed_expansion_score_factor: 0.5 * /move_group/planner_configs/KPIECE/goal_bias: 0.05 * /move_group/planner_configs/KPIECE/min_valid_path_fraction: 0.5 * /move_group/planner_configs/KPIECE/range: 0.0 * /move_group/planner_configs/KPIECE/type: geometric::KPIECE * /move_group/planner_configs/LBKPIECE/border_fraction: 0.9 * /move_group/planner_configs/LBKPIECE/min_valid_path_fraction: 0.5 * /move_group/planner_configs/LBKPIECE/range: 0.0 * /move_group/planner_configs/LBKPIECE/type: geometric::LBKPIECE * /move_group/planner_configs/LBTRRT/epsilon: 0.4 * /move_group/planner_configs/LBTRRT/goal_bias: 0.05 * /move_group/planner_configs/LBTRRT/range: 0.0 * /move_group/planner_configs/LBTRRT/type: geometric::LBTRRT * /move_group/planner_configs/LazyPRM/range: 0.0 * /move_group/planner_configs/LazyPRM/type: geometric::LazyPRM * /move_group/planner_configs/LazyPRMstar/type: geometric::LazyPR... * /move_group/planner_configs/PDST/type: geometric::PDST * /move_group/planner_configs/PRM/max_nearest_neighbors: 10 * /move_group/planner_configs/PRM/type: geometric::PRM * /move_group/planner_configs/PRMstar/type: geometric::PRMstar * /move_group/planner_configs/ProjEST/goal_bias: 0.05 * /move_group/planner_configs/ProjEST/range: 0.0 * /move_group/planner_configs/ProjEST/type: geometric::ProjEST * /move_group/planner_configs/RRT/goal_bias: 0.05 * /move_group/planner_configs/RRT/range: 0.0 * /move_group/planner_configs/RRT/type: geometric::RRT * /move_group/planner_configs/RRTConnect/range: 0.0 * /move_group/planner_configs/RRTConnect/type: geometric::RRTCon... * /move_group/planner_configs/RRTstar/delay_collision_checking: 1 * /move_group/planner_configs/RRTstar/goal_bias: 0.05 * /move_group/planner_configs/RRTstar/range: 0.0 * /move_group/planner_configs/RRTstar/type: geometric::RRTstar * /move_group/planner_configs/SBL/range: 0.0 * /move_group/planner_configs/SBL/type: geometric::SBL * /move_group/planner_configs/SPARS/dense_delta_fraction: 0.001 * /move_group/planner_configs/SPARS/max_failures: 1000 * /move_group/planner_configs/SPARS/sparse_delta_fraction: 0.25 * /move_group/planner_configs/SPARS/stretch_factor: 3.0 * /move_group/planner_configs/SPARS/type: geometric::SPARS * /move_group/planner_configs/SPARStwo/dense_delta_fraction: 0.001 * /move_group/planner_configs/SPARStwo/max_failures: 5000 * /move_group/planner_configs/SPARStwo/sparse_delta_fraction: 0.25 * /move_group/planner_configs/SPARStwo/stretch_factor: 3.0 * /move_group/planner_configs/SPARStwo/type: geometric::SPARStwo * /move_group/planner_configs/STRIDE/degree: 16 * /move_group/planner_configs/STRIDE/estimated_dimension: 0.0 * /move_group/planner_configs/STRIDE/goal_bias: 0.05 * /move_group/planner_configs/STRIDE/max_degree: 18 * /move_group/planner_configs/STRIDE/max_pts_per_leaf: 6 * /move_group/planner_configs/STRIDE/min_degree: 12 * /move_group/planner_configs/STRIDE/min_valid_path_fraction: 0.2 * /move_group/planner_configs/STRIDE/range: 0.0 * /move_group/planner_configs/STRIDE/type: geometric::STRIDE * /move_group/planner_configs/STRIDE/use_projected_distance: 0 * /move_group/planner_configs/TRRT/frountierNodeRatio: 0.1 * /move_group/planner_configs/TRRT/frountier_threshold: 0.0 * /move_group/planner_configs/TRRT/goal_bias: 0.05 * /move_group/planner_configs/TRRT/init_temperature: 10e-6 * /move_group/planner_configs/TRRT/k_constant: 0.0 * /move_group/planner_configs/TRRT/max_states_failed: 10 * /move_group/planner_configs/TRRT/min_temperature: 10e-10 * /move_group/planner_configs/TRRT/range: 0.0 * /move_group/planner_configs/TRRT/temp_change_factor: 2.0 * /move_group/planner_configs/TRRT/type: geometric::TRRT * /move_group/planning_plugin: ompl_interface/OM... * /move_group/planning_scene_monitor/publish_geometry_updates: True * /move_group/planning_scene_monitor/publish_planning_scene: True * /move_group/planning_scene_monitor/publish_state_updates: True * /move_group/planning_scene_monitor/publish_transforms_updates: True * /move_group/request_adapters: industrial_trajec... * /move_group/sample_duration: 0.005 * /move_group/sensors: [{'point_subsampl... * /move_group/start_state_max_bounds_error: 0.1 * /move_group/trajectory_execution/allowed_execution_duration_scaling: 4.0 * /move_group/trajectory_execution/allowed_goal_duration_margin: 0.5 * /move_group/trajectory_execution/allowed_start_tolerance: 0.01 * /move_group/trajectory_execution/execution_duration_monitoring: False * /robot_description: <?xml version="1.... * /robot_description_kinematics/manipulator_i5/kinematics_solver: kdl_kinematics_pl... * /robot_description_kinematics/manipulator_i5/kinematics_solver_search_resolution: 0.005 * /robot_description_kinematics/manipulator_i5/kinematics_solver_timeout: 0.005 * /robot_description_planning/joint_limits/foreArm_joint/has_acceleration_limits: False * /robot_description_planning/joint_limits/foreArm_joint/has_velocity_limits: True * /robot_description_planning/joint_limits/foreArm_joint/max_acceleration: 30 * /robot_description_planning/joint_limits/foreArm_joint/max_velocity: 3.14 * /robot_description_planning/joint_limits/shoulder_joint/has_acceleration_limits: False * /robot_description_planning/joint_limits/shoulder_joint/has_velocity_limits: True * /robot_description_planning/joint_limits/shoulder_joint/max_acceleration: 30 * /robot_description_planning/joint_limits/shoulder_joint/max_velocity: 3.14 * /robot_description_planning/joint_limits/upperArm_joint/has_acceleration_limits: False * /robot_description_planning/joint_limits/upperArm_joint/has_velocity_limits: True * /robot_description_planning/joint_limits/upperArm_joint/max_acceleration: 30 * /robot_description_planning/joint_limits/upperArm_joint/max_velocity: 3.14 * /robot_description_planning/joint_limits/wrist1_joint/has_acceleration_limits: False * /robot_description_planning/joint_limits/wrist1_joint/has_velocity_limits: True * /robot_description_planning/joint_limits/wrist1_joint/max_acceleration: 25 * /robot_description_planning/joint_limits/wrist1_joint/max_velocity: 2.6 * /robot_description_planning/joint_limits/wrist2_joint/has_acceleration_limits: False * /robot_description_planning/joint_limits/wrist2_joint/has_velocity_limits: True * /robot_description_planning/joint_limits/wrist2_joint/max_acceleration: 25 * /robot_description_planning/joint_limits/wrist2_joint/max_velocity: 2.6 * /robot_description_planning/joint_limits/wrist3_joint/has_acceleration_limits: False * /robot_description_planning/joint_limits/wrist3_joint/has_velocity_limits: True * /robot_description_planning/joint_limits/wrist3_joint/max_acceleration: 25 * /robot_description_planning/joint_limits/wrist3_joint/max_velocity: 2.6 * /robot_description_semantic: <?xml version="1.... * /robot_name: aubo_i5 * /rosdistro: melodic * /rosversion: 1.14.13 * /rviz_tian_28357_5613264337159122920/manipulator_i5/kinematics_solver: kdl_kinematics_pl... * /rviz_tian_28357_5613264337159122920/manipulator_i5/kinematics_solver_search_resolution: 0.005 * /rviz_tian_28357_5613264337159122920/manipulator_i5/kinematics_solver_timeout: 0.005 NODES / aubo_driver (aubo_driver/aubo_driver) aubo_joint_trajectory_action (aubo_controller/aubo_joint_trajectory_action) aubo_robot_simulator (aubo_controller/aubo_robot_simulator) move_group (moveit_ros_move_group/move_group) robot_state_publisher (robot_state_publisher/robot_state_publisher) rviz_tian_28357_5613264337159122920 (rviz/rviz) auto-starting new master process[master]: started with pid [28371] ROS_MASTER_URI=http://localhost:11311 setting /run_id to 69be2d1c-b7d0-11f0-a111-2c9464039e34 process[rosout-1]: started with pid [28382] started core service [/rosout] process[aubo_robot_simulator-2]: started with pid [28389] process[aubo_joint_trajectory_action-3]: started with pid [28390] process[aubo_driver-4]: started with pid [28391] process[robot_state_publisher-5]: started with pid [28393] [ INFO] [1762076620.975289494]: Adding shoulder_joint to list parameter [ INFO] [1762076620.976437205]: Adding upperArm_joint to list parameter [ INFO] [1762076620.976450447]: Adding foreArm_joint to list parameter [ INFO] [1762076620.976461219]: Adding wrist1_joint to list parameter [ INFO] [1762076620.976468429]: Adding wrist2_joint to list parameter [ INFO] [1762076620.976475474]: Adding wrist3_joint to list parameter [ INFO] [1762076620.976499775]: Found user-specified joint names in 'controller_joint_names': [shoulder_joint, upperArm_joint, foreArm_joint, wrist1_joint, wrist2_joint, wrist3_joint] [ INFO] [1762076620.976511379]: Filtered joint names to 6 joints process[move_group-6]: started with pid [28402] process[rviz_tian_28357_5613264337159122920-7]: started with pid [28412] log4cplus:ERROR could not open file ./config/tracelog.properties log4cplus:ERROR No appenders could be found for logger (ourrobottrace). log4cplus:ERROR Please initialize the log4cplus system properly. [ INFO] [1762076621.017125306]: Loading robot model 'aubo_i5'... [ WARN] [1762076621.017989247]: Skipping virtual joint 'base_link' because its child frame 'base_link' does not match the URDF frame 'world' [ INFO] [1762076621.018004978]: No root/virtual joint specified in SRDF. Assuming fixed joint [ INFO] [1762076621.068145876]: rviz version 1.13.30 [ INFO] [1762076621.068293956]: compiled against Qt version 5.9.5 [ INFO] [1762076621.068302158]: compiled against OGRE version 1.9.0 (Ghadamon) [ INFO] [1762076621.071714956]: Forcing OpenGl version 0. [INFO] [1762076621.293396]: Setting publish rate (hz) based on parameter: 50.000000 [INFO] [1762076621.294459]: Simulating manipulator with 6 joints: shoulder_joint, upperArm_joint, foreArm_joint, wrist1_joint, wrist2_joint, wrist3_joint [INFO] [1762076621.295511]: Setting motion update rate (hz): 200.000000 [WARN] [1762076621.296947]: Invalid initial_joint_state parameter, defaulting to all-zeros [INFO] [1762076621.297546]: Using initial joint state: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] [INFO] [1762076621.302005]: Starting motion worker in motion controller simulator [INFO] [1762076621.303133]: The velocity scale factor of the trajetory is: 1.000000 [INFO] [1762076621.306835]: Creating joint trajectory subscriber [INFO] [1762076621.308616]: Enable Switch [INFO] [1762076621.354461]: Clean up init [ INFO] [1762076621.490932917]: Stereo is NOT SUPPORTED [ INFO] [1762076621.490982853]: OpenGL device: NVIDIA GeForce GTX 1050 Ti/PCIe/SSE2 [ INFO] [1762076621.490998617]: OpenGl version: 4.6 (GLSL 4.6). [ INFO] [1762076621.527283296]: Publishing maintained planning scene on 'monitored_planning_scene' [ INFO] [1762076621.528627766]: MoveGroup debug mode is OFF Starting planning scene monitors... [ INFO] [1762076621.528645797]: Starting planning scene monitor [ INFO] [1762076621.529857849]: Listening to '/planning_scene' [ INFO] [1762076621.529872699]: Starting world geometry update monitor for collision objects, attached objects, octomap updates. [ INFO] [1762076621.530897643]: Listening to '/collision_object' [ INFO] [1762076621.531963313]: Listening to '/planning_scene_world' for planning scene world geometry [ INFO] [1762076622.535972708]: Listening to '/head_mount_kinect/depth_registered/points' using message filter with target frame 'world ' [ INFO] [1762076622.538405886]: Listening to '/attached_collision_object' for attached collision objects Planning scene monitors started. [ INFO] [1762076622.554456326]: Initializing OMPL interface using ROS parameters [ INFO] [1762076622.565566122]: Using planning interface 'OMPL' [ INFO] [1762076622.567477284]: Constructing N point filter [ INFO] [1762076622.568748991]: Param 'default_workspace_bounds' was not set. Using default value: 10 [ INFO] [1762076622.569256661]: Param 'start_state_max_bounds_error' was set to 0.1 [ INFO] [1762076622.569523339]: Param 'start_state_max_dt' was not set. Using default value: 0.5 [ INFO] [1762076622.570007206]: Param 'start_state_max_dt' was not set. Using default value: 0.5 [ INFO] [1762076622.570270603]: Param 'jiggle_fraction' was set to 0.05 [ INFO] [1762076622.570527226]: Param 'max_sampling_attempts' was not set. Using default value: 100 [ INFO] [1762076622.570586021]: Using planning request adapter 'Trajectory filter 'UniformSampleFilter' of type 'UniformSampleFilter'' [ INFO] [1762076622.570597617]: Using planning request adapter 'Add Time Parameterization' [ INFO] [1762076622.570606717]: Using planning request adapter 'Fix Workspace Bounds' [ INFO] [1762076622.570622499]: Using planning request adapter 'Fix Start State Bounds' [ INFO] [1762076622.570642885]: Using planning request adapter 'Fix Start State In Collision' [ INFO] [1762076622.570662345]: Using planning request adapter 'Fix Start State Path Constraints' [ INFO] [1762076622.867106380]: Added FollowJointTrajectory controller for aubo_i5_controller [ INFO] [1762076622.867371382]: Returned 1 controllers in list [ INFO] [1762076622.900353684]: Trajectory execution is managing controllers Loading 'move_group/ApplyPlanningSceneService'... Loading 'move_group/ClearOctomapService'... Loading 'move_group/MoveGroupCartesianPathService'... Loading 'move_group/MoveGroupExecuteTrajectoryAction'... Loading 'move_group/MoveGroupGetPlanningSceneService'... Loading 'move_group/MoveGroupKinematicsService'... Loading 'move_group/MoveGroupMoveAction'... Loading 'move_group/MoveGroupPickPlaceAction'... Loading 'move_group/MoveGroupPlanService'... Loading 'move_group/MoveGroupQueryPlannersService'... Loading 'move_group/MoveGroupStateValidationService'... [ INFO] [1762076622.955447007]: ******************************************************** * MoveGroup using: * - ApplyPlanningSceneService * - ClearOctomapService * - CartesianPathService * - ExecuteTrajectoryAction * - GetPlanningSceneService * - KinematicsService * - MoveAction * - PickPlaceAction * - MotionPlanService * - QueryPlannersService * - StateValidationService ******************************************************** [ INFO] [1762076622.955481294]: MoveGroup context using planning plugin ompl_interface/OMPLPlanner [ INFO] [1762076622.955495059]: MoveGroup context initialization complete You can start planning now! [ INFO] [1762076624.756700336]: Loading robot model 'aubo_i5'... [ WARN] [1762076624.756746443]: Skipping virtual joint 'base_link' because its child frame 'base_link' does not match the URDF frame 'world' [ INFO] [1762076624.756771581]: No root/virtual joint specified in SRDF. Assuming fixed joint [ INFO] [1762076625.264448710]: Starting planning scene monitor [ INFO] [1762076625.266530944]: Listening to '/move_group/monitored_planning_scene' [ INFO] [1762076625.686336464]: Constructing new MoveGroup connection for group 'manipulator_i5' in namespace '' [ INFO] [1762076626.877045917]: Ready to take commands for planning group manipulator_i5. [ INFO] [1762076626.877183789]: Looking around: no [ INFO] [1762076626.877245273]: Replanning: no [ INFO] [1762076643.174830115]: Combined planning and execution request received for MoveGroup action. Forwarding to planning and execution pipeline. [ INFO] [1762076643.175277031]: Planning attempt 1 of at most 1 [ INFO] [1762076643.176738253]: Using a sample_duration value of 0.005 [ INFO] [1762076643.180184117]: Planner configuration 'manipulator_i5' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed. [ INFO] [1762076643.182625931]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076643.182831809]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076643.182985284]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076643.183155704]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076643.196664477]: RRTConnect: Created 4 states (2 start + 2 goal) [ INFO] [1762076643.196880812]: RRTConnect: Created 5 states (2 start + 3 goal) [ INFO] [1762076643.197507341]: RRTConnect: Created 5 states (2 start + 3 goal) [ INFO] [1762076643.197718645]: RRTConnect: Created 4 states (2 start + 2 goal) [ INFO] [1762076643.198230738]: ParallelPlan::solve(): Solution found by one or more threads in 0.016307 seconds [ INFO] [1762076643.199047044]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076643.199217949]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076643.199394720]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076643.199539848]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076643.203516801]: RRTConnect: Created 5 states (2 start + 3 goal) [ INFO] [1762076643.203977054]: RRTConnect: Created 4 states (2 start + 2 goal) [ INFO] [1762076643.204789531]: RRTConnect: Created 4 states (2 start + 2 goal) [ INFO] [1762076643.205275657]: RRTConnect: Created 5 states (2 start + 3 goal) [ INFO] [1762076643.205579430]: ParallelPlan::solve(): Solution found by one or more threads in 0.006801 seconds [ INFO] [1762076643.206133622]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076643.206314425]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076643.210023941]: RRTConnect: Created 4 states (2 start + 2 goal) [ INFO] [1762076643.210188376]: RRTConnect: Created 4 states (2 start + 2 goal) [ INFO] [1762076643.210713824]: ParallelPlan::solve(): Solution found by one or more threads in 0.004754 seconds [ INFO] [1762076643.226914630]: SimpleSetup: Path simplification took 0.015846 seconds and changed from 3 to 2 states [ INFO] [1762076643.229838490]: Interpolated time exceeds original trajectory (quitting), original: 1.64812 final interpolated time: 1.65 [ INFO] [1762076643.229965778]: Uniform sampling, resample duraction: 0.005 input traj. size: 4 output traj. size: 331 [ INFO] [1762076643.241589040]: Disabling trajectory recording [ INFO] [1762076643.249267809]: Received new goal [ INFO] [1762076643.249383221]: Publishing trajectory [INFO] [1762076643.254872]: Received trajectory with 331 points [INFO] [1762076643.257125]: Velocity scale factor: 1.0 [ERROR] [1762076643.263622]: Unexpected exception: int() argument must be a string, a bytes-like object or a number, not 'Duration' [INFO] [1762076643.284360]: Added new trajectory with 331 points [ INFO] [1762076645.072204824]: Inside goal constraints, stopped moving, return success for action [ INFO] [1762076645.073066959]: Controller aubo_i5_controller successfully finished [ INFO] [1762076645.131429419]: Completed trajectory execution with status SUCCEEDED ... [ INFO] [1762076645.141135973]: trajectory execution status: stop1 [ INFO] [1762076645.141144669]: Received event 'stop' [ERROR] [1762076645.141260396]: To transition to an aborted state, the goal must be in a preempting or active state, it is currently in state: 3 [ INFO] [1762076645.390044200]: Combined planning and execution request received for MoveGroup action. Forwarding to planning and execution pipeline. [ INFO] [1762076645.390232795]: Planning attempt 1 of at most 1 [ INFO] [1762076645.391435158]: Planner configuration 'manipulator_i5' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed. [ INFO] [1762076645.392501038]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076645.392765325]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076645.392996916]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076645.393232737]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076645.405152731]: RRTConnect: Created 4 states (2 start + 2 goal) [ INFO] [1762076645.406623163]: RRTConnect: Created 5 states (2 start + 3 goal) [ INFO] [1762076645.407075831]: RRTConnect: Created 4 states (2 start + 2 goal) [ INFO] [1762076645.407262705]: RRTConnect: Created 5 states (2 start + 3 goal) [ INFO] [1762076645.407673599]: ParallelPlan::solve(): Solution found by one or more threads in 0.015443 seconds [ INFO] [1762076645.408471126]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076645.408854773]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076645.409019127]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076645.409187565]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076645.410172203]: RRTConnect: Created 4 states (2 start + 2 goal) [ INFO] [1762076645.414208863]: RRTConnect: Created 4 states (2 start + 2 goal) [ INFO] [1762076645.414576171]: RRTConnect: Created 5 states (2 start + 3 goal) [ INFO] [1762076645.415038020]: RRTConnect: Created 5 states (2 start + 3 goal) [ INFO] [1762076645.415411858]: ParallelPlan::solve(): Solution found by one or more threads in 0.007207 seconds [ INFO] [1762076645.415915443]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076645.416264033]: RRTConnect: Starting planning with 1 states already in datastructure [ INFO] [1762076645.420120818]: RRTConnect: Created 5 states (2 start + 3 goal) [ INFO] [1762076645.420431203]: RRTConnect: Created 5 states (2 start + 3 goal) [ INFO] [1762076645.420816818]: ParallelPlan::solve(): Solution found by one or more threads in 0.005031 seconds [ INFO] [1762076645.428721527]: SimpleSetup: Path simplification took 0.007722 seconds and changed from 3 to 2 states [ INFO] [1762076645.431648243]: Interpolated time exceeds original trajectory (quitting), original: 2.78717 final interpolated time: 2.79 [ INFO] [1762076645.431751832]: Uniform sampling, resample duraction: 0.005 input traj. size: 4 output traj. size: 559 [ INFO] [1762076645.450663603]: Received new goal [ INFO] [1762076645.450732490]: Publishing trajectory [INFO] [1762076645.467334]: Received trajectory with 559 points [INFO] [1762076645.469154]: Velocity scale factor: 1.0 [ERROR] [1762076645.480497]: Unexpected exception: int() argument must be a string, a bytes-like object or a number, not 'Duration' [ERROR] [1762076645.492113]: Unexpected exception: int() argument must be a string, a bytes-like object or a number, not 'Duration' [INFO] [1762076645.493956]: Added new trajectory with 559 points [ERROR] [1762076645.494570]: Unexpected exception: int() argument must be a string, a bytes-like object or a number, not 'Duration'
11-03
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值