Robotics StackExchange | Archived questions

sequence_move_group keeps Aborting

Hello Developers,

I am trying to use `sequencemovegroup' action client to move my manipulator to a certain location. I recycled the Pilz Industrial Motion Planner in order to provide a sequence of way-points to pass through. While the Pilz tutorial works for moving the robot to a desired joint configuration, when I give the same set (all zero joint-angle) configuration, when printing the action client status, I see that it is 1 (Active) for some amount of time and then its status changes to 4 (Aborted).

I am unable to find the cause for the trajectory following to be rejected. I see that the joint torques are not hitting their respective thresholds.

Any help in diagnosing the cause would be most appreciated.

Thank you

Setup:

Demo python script

#!/usr/bin/env python
from geometry_msgs.msg import Pose, Point
from pilz_robot_programming import *
import math
import rospy

__REQUIRED_API_VERSION__ = "1"  # API version
__ROBOT_VELOCITY__ = 0.5        # velocity of the robot

# main program
def start_program():
    print(r.get_current_pose()) # print the current position of thr robot in the terminal
    # Simple ptp movement
    r.move(Ptp(goal=[0, 0, 0, 0, 0, 0, 0], vel_scale=0.05))

    start_joint_values = r.get_current_joint_states()

if __name__ == "__main__":
    # init a rosnode
    rospy.init_node('robot_program_node')

    # initialisation
    r = My_Robot(__REQUIRED_API_VERSION__)  # instance of the robot

    # start the main program
    start_program()

Topics being recorded

"/gazebo/link_states","/sequence_move_group/status","/uwarl_a/robotnik_base_control/odom","/uwarl_a/robotnik_base_control/cmd_vel","/uwarl_a/joint_states"

ROS environment variables:

┌─(~)──────────────────────────────────────────────────────────────────────────────────────────────(arnab@arl-System-Product-Name:pts/8)─┐
└─(13:08:22)──> env | grep ROS                                                                                         1 ↵ ──(Fri,Aug04)─┘
ROS_CORE_HOSTER=LOCAL-HOSTS
ROS_SUMMIT_IN_NETWORK_IP=192.168.1.11
ROS_WAM_IN_NETWORK_IP=192.168.1.10
ROS_DECK_IN_NETWORK_IP=192.168.1.15
ROS_JX_IN_NETWORK_PARALLEL_PC_IP=192.168.1.100
ROS_EXTERNAL_PC_IN_NETWORK_IP=192.168.1.100
ROS_CATKIN_WS=/home/arnab/UWARL_catkin_ws
ROS_DISTRO=noetic
PYTHONPATH_ROS=/usr/bin/python3
ROS_IP=localhost
ROS_HOSTNAME=localhost
ROS_MASTER_URI=http://localhost:11311/
ROS_ETC_DIR=/opt/ros/noetic/etc/ros
ROS_PACKAGE_PATH=/home/arnab/UWARL_catkin_ws/src/uwarl-barrett_wam_msgs:/home/arnab/UWARL_catkin_ws/src/uwarl-barrett_wam_hw/barrett_hand_node:/home/arnab/UWARL_catkin_ws/src/multimap_server_msgs:/home/arnab/UWARL_catkin_ws/src/uwarl-multimap_server:/home/arnab/UWARL_catkin_ws/src/pilz_tutorial:/home/arnab/UWARL_catkin_ws/src/uwarl-realsense_ros/realsense2_camera:/home/arnab/UWARL_catkin_ws/src/uwarl-realsense_ros/realsense2_description:/home/arnab/UWARL_catkin_ws/src/uwarl-robotnik_msgs:/home/arnab/UWARL_catkin_ws/src/uwarl-robot_localization_utils:/home/arnab/UWARL_catkin_ws/src/uwarl-robotnik_sensors:/home/arnab/UWARL_catkin_ws/src/waterloo_steel/waterloo_steel_util/rosbag_recorder:/home/arnab/UWARL_catkin_ws/src/uwarl-realsense_ros/jx-rs4se:/home/arnab/UWARL_catkin_ws/src/uwarl-summit_xl_common/summit_xl_common:/home/arnab/UWARL_catkin_ws/src/uwarl-summit_xl_robot/summit_xl_controller:/home/arnab/UWARL_catkin_ws/src/uwarl-summit_xl_common/moveit/summit_xl_j2s6s200_moveit_config:/home/arnab/UWARL_catkin_ws/src/uwarl-summit_xl_common/moveit/summit_xl_j2s6s300_moveit_config:/home/arnab/UWARL_catkin_ws/src/uwarl-summit_xl_common/moveit/summit_xl_j2s7s300_moveit_config:/home/arnab/UWARL_catkin_ws/src/uwarl-summit_xl_common/summit_xl_localization:/home/arnab/UWARL_catkin_ws/src/uwarl-summit_xl_common/summit_xl_navigation:/home/arnab/UWARL_catkin_ws/src/waterloo_steel/waterloo_steel_interface/summit_xl_pad:/home/arnab/UWARL_catkin_ws/src/uwarl-summit_xl_common/summit_xl_perception:/home/arnab/UWARL_catkin_ws/src/uwarl-summit_xl_common/summit_xl_robot_local_control:/home/arnab/UWARL_catkin_ws/src/system_monitor:/home/arnab/UWARL_catkin_ws/src/velodyne_simulator/velodyne_description:/home/arnab/UWARL_catkin_ws/src/velodyne_simulator/velodyne_gazebo_plugins:/home/arnab/UWARL_catkin_ws/src/velodyne_simulator/velodyne_simulator:/home/arnab/UWARL_catkin_ws/src/wagon_tf_publisher:/home/arnab/UWARL_catkin_ws/src/uwarl-barrett_wam_hw/wam_node:/home/arnab/UWARL_catkin_ws/src/waterloo_steel/waterloo_steel_demo/waterloo_steel_analyzer:/home/arnab/UWARL_catkin_ws/src/waterloo_steel/waterloo_steel_viz/waterloo_steel_control:/home/arnab/UWARL_catkin_ws/src/waterloo_steel/waterloo_steel_viz/waterloo_steel_description:/home/arnab/UWARL_catkin_ws/src/waterloo_steel/waterloo_steel_viz/waterloo_steel_gazebo:/home/arnab/UWARL_catkin_ws/src/waterloo_steel/waterloo_steel_viz/waterloo_steel_moveit_config:/home/arnab/UWARL_catkin_ws/src/waterloo_steel/waterloo_steel_viz/waterloo_steel_sim_bringup:/home/arnab/UWARL_catkin_ws/src/uwarl-summit_xl_robot/waterloo_steel_summit_bringup:/home/arnab/UWARL_catkin_ws/src/waterloo_steel/waterloo_steel_demo/waterloo_steel_supervisor:/opt/ros/noetic/share
ROS_PYTHON_VERSION=3
ROS_VERSION=1
ROS_ROOT=/opt/ros/noetic/share/ros
ROSLISP_PACKAGE_DIRECTORIES=/home/arnab/UWARL_catkin_ws/devel/share/common-lisp

Terminal Output after roslaunch:

┌─(~)───────────────────────────────────(arnab@arl-System-Product-Name:pts/0)─┐
└─(11:03:04)──> roslaunch waterloo_steel_sim_bringup waterloo_steel_complete_cart.launch
... logging to /home/arnab/.ros/log/d45ada00-32e7-11ee-8f31-59374263d0ff/roslaunch-arl-System-Product-Name-55514.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.
xacro: in-order processing became default in ROS Melodic. You can drop the option.
started roslaunch server http://localhost:42503/

SUMMARY
========

PARAMETERS
 * /gazebo/enable_ros_network: True
 * /joint_state_publisher/use_gui: False
 * /move_group/allow_trajectory_execution: True
 * /move_group/capabilities: 
 * /move_group/controller_list: [{'name': '/uwarl...
 * /move_group/default_planning_pipeline: ompl
 * /move_group/disable_capabilities: 
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/base_yaw_joint/d: 10
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/base_yaw_joint/i: 2.5
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/base_yaw_joint/i_clamp: 0
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/base_yaw_joint/p: 900
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/elbow_pitch_joint/d: 12
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/elbow_pitch_joint/i: 2.5
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/elbow_pitch_joint/i_clamp: 0
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/elbow_pitch_joint/p: 500
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/palm_yaw_joint/d: 0.05
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/palm_yaw_joint/i: 0.1
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/palm_yaw_joint/i_clamp: 0
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/palm_yaw_joint/p: 8
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_pitch_joint/d: 20
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_pitch_joint/i: 5
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_pitch_joint/i_clamp: 0
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_pitch_joint/p: 2500
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_yaw_joint/d: 15
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_yaw_joint/i: 2
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_yaw_joint/i_clamp: 0
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_yaw_joint/p: 600
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_pitch_joint/d: 5
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_pitch_joint/i: 2.5
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_pitch_joint/i_clamp: 0
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_pitch_joint/p: 100
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_yaw_joint/d: 12
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_yaw_joint/i: 2.5
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_yaw_joint/i_clamp: 0
 * /move_group/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_yaw_joint/p: 500
 * /move_group/eff_based_pos_traj_controller/joints: ['uwarl_a_wam/bas...
 * /move_group/eff_based_pos_traj_controller/type: effort_controller...
 * /move_group/generic_hw_control_loop/cycle_time_error_threshold: 0.01
 * /move_group/generic_hw_control_loop/loop_hz: 300
 * /move_group/hardware_interface/joints: ['uwarl_a_wam/bas...
 * /move_group/hardware_interface/sim_control_mode: 0
 * /move_group/joint_state_controller/publish_rate: 500
 * /move_group/joint_state_controller/type: joint_state_contr...
 * /move_group/max_range: 5.0
 * /move_group/monitor_dynamics: False
 * /move_group/moveit_controller_manager: moveit_simple_con...
 * /move_group/moveit_manage_controllers: True
 * /move_group/octomap_resolution: 0.025
 * /move_group/planning_pipelines/chomp/collision_clearance: 0.2
 * /move_group/planning_pipelines/chomp/collision_threshold: 0.07
 * /move_group/planning_pipelines/chomp/enable_failure_recovery: False
 * /move_group/planning_pipelines/chomp/jiggle_fraction: 0.05
 * /move_group/planning_pipelines/chomp/joint_update_limit: 0.1
 * /move_group/planning_pipelines/chomp/learning_rate: 0.01
 * /move_group/planning_pipelines/chomp/max_iterations: 200
 * /move_group/planning_pipelines/chomp/max_iterations_after_collision_free: 5
 * /move_group/planning_pipelines/chomp/max_recovery_attempts: 5
 * /move_group/planning_pipelines/chomp/obstacle_cost_weight: 1.0
 * /move_group/planning_pipelines/chomp/planning_plugin: chomp_interface/C...
 * /move_group/planning_pipelines/chomp/planning_time_limit: 10.0
 * /move_group/planning_pipelines/chomp/pseudo_inverse_ridge_factor: 1e-4
 * /move_group/planning_pipelines/chomp/request_adapters: default_planner_r...
 * /move_group/planning_pipelines/chomp/ridge_factor: 0.0
 * /move_group/planning_pipelines/chomp/smoothness_cost_acceleration: 1.0
 * /move_group/planning_pipelines/chomp/smoothness_cost_jerk: 0.0
 * /move_group/planning_pipelines/chomp/smoothness_cost_velocity: 0.0
 * /move_group/planning_pipelines/chomp/smoothness_cost_weight: 0.1
 * /move_group/planning_pipelines/chomp/start_state_max_bounds_error: 0.1
 * /move_group/planning_pipelines/chomp/use_pseudo_inverse: False
 * /move_group/planning_pipelines/chomp/use_stochastic_descent: True
 * /move_group/planning_pipelines/ompl/BHand/longest_valid_segment_fraction: 0.005
 * /move_group/planning_pipelines/ompl/BHand/planner_configs: ['AnytimePathShor...
 * /move_group/planning_pipelines/ompl/BHand/projection_evaluator: joints(uwarl_a_wa...
 * /move_group/planning_pipelines/ompl/WAM/longest_valid_segment_fraction: 0.005
 * /move_group/planning_pipelines/ompl/WAM/planner_configs: ['AnytimePathShor...
 * /move_group/planning_pipelines/ompl/WAM/projection_evaluator: joints(uwarl_a_wa...
 * /move_group/planning_pipelines/ompl/jiggle_fraction: 0.05
 * /move_group/planning_pipelines/ompl/planner_configs/ABITstar/delay_rewiring_to_first_solution: 0
 * /move_group/planning_pipelines/ompl/planner_configs/ABITstar/drop_unconnected_samples_on_prune: 0
 * /move_group/planning_pipelines/ompl/planner_configs/ABITstar/find_approximate_solutions: 0
 * /move_group/planning_pipelines/ompl/planner_configs/ABITstar/inflation_scaling_parameter: 10
 * /move_group/planning_pipelines/ompl/planner_configs/ABITstar/initial_inflation_factor: 1000000
 * /move_group/planning_pipelines/ompl/planner_configs/ABITstar/prune_threshold_as_fractional_cost_change: 0.1
 * /move_group/planning_pipelines/ompl/planner_configs/ABITstar/rewire_factor: 1.001
 * /move_group/planning_pipelines/ompl/planner_configs/ABITstar/samples_per_batch: 100
 * /move_group/planning_pipelines/ompl/planner_configs/ABITstar/stop_on_each_solution_improvement: 0
 * /move_group/planning_pipelines/ompl/planner_configs/ABITstar/truncation_scaling_parameter: 5.0
 * /move_group/planning_pipelines/ompl/planner_configs/ABITstar/type: geometric::ABITstar
 * /move_group/planning_pipelines/ompl/planner_configs/ABITstar/use_graph_pruning: 1
 * /move_group/planning_pipelines/ompl/planner_configs/ABITstar/use_just_in_time_sampling: 0
 * /move_group/planning_pipelines/ompl/planner_configs/ABITstar/use_k_nearest: 1
 * /move_group/planning_pipelines/ompl/planner_configs/ABITstar/use_strict_queue_ordering: 0
 * /move_group/planning_pipelines/ompl/planner_configs/AITstar/find_approximate_solutions: 0
 * /move_group/planning_pipelines/ompl/planner_configs/AITstar/rewire_factor: 1.001
 * /move_group/planning_pipelines/ompl/planner_configs/AITstar/samples_per_batch: 100
 * /move_group/planning_pipelines/ompl/planner_configs/AITstar/set_max_num_goals: 1
 * /move_group/planning_pipelines/ompl/planner_configs/AITstar/type: geometric::AITstar
 * /move_group/planning_pipelines/ompl/planner_configs/AITstar/use_graph_pruning: 1
 * /move_group/planning_pipelines/ompl/planner_configs/AITstar/use_k_nearest: 1
 * /move_group/planning_pipelines/ompl/planner_configs/AnytimePathShortening/hybridize: True
 * /move_group/planning_pipelines/ompl/planner_configs/AnytimePathShortening/max_hybrid_paths: 24
 * /move_group/planning_pipelines/ompl/planner_configs/AnytimePathShortening/num_planners: 4
 * /move_group/planning_pipelines/ompl/planner_configs/AnytimePathShortening/planners: 
 * /move_group/planning_pipelines/ompl/planner_configs/AnytimePathShortening/shortcut: True
 * /move_group/planning_pipelines/ompl/planner_configs/AnytimePathShortening/type: geometric::Anytim...
 * /move_group/planning_pipelines/ompl/planner_configs/BFMT/balanced: 0
 * /move_group/planning_pipelines/ompl/planner_configs/BFMT/cache_cc: 1
 * /move_group/planning_pipelines/ompl/planner_configs/BFMT/extended_fmt: 1
 * /move_group/planning_pipelines/ompl/planner_configs/BFMT/heuristics: 1
 * /move_group/planning_pipelines/ompl/planner_configs/BFMT/nearest_k: 1
 * /move_group/planning_pipelines/ompl/planner_configs/BFMT/num_samples: 1000
 * /move_group/planning_pipelines/ompl/planner_configs/BFMT/optimality: 1
 * /move_group/planning_pipelines/ompl/planner_configs/BFMT/radius_multiplier: 1.0
 * /move_group/planning_pipelines/ompl/planner_configs/BFMT/type: geometric::BFMT
 * /move_group/planning_pipelines/ompl/planner_configs/BITstar/delay_rewiring_to_first_solution: 0
 * /move_group/planning_pipelines/ompl/planner_configs/BITstar/drop_unconnected_samples_on_prune: 0
 * /move_group/planning_pipelines/ompl/planner_configs/BITstar/find_approximate_solutions: 0
 * /move_group/planning_pipelines/ompl/planner_configs/BITstar/prune_threshold_as_fractional_cost_change: 0.1
 * /move_group/planning_pipelines/ompl/planner_configs/BITstar/rewire_factor: 1.001
 * /move_group/planning_pipelines/ompl/planner_configs/BITstar/samples_per_batch: 100
 * /move_group/planning_pipelines/ompl/planner_configs/BITstar/stop_on_each_solution_improvement: 0
 * /move_group/planning_pipelines/ompl/planner_configs/BITstar/type: geometric::BITstar
 * /move_group/planning_pipelines/ompl/planner_configs/BITstar/use_graph_pruning: 1
 * /move_group/planning_pipelines/ompl/planner_configs/BITstar/use_just_in_time_sampling: 0
 * /move_group/planning_pipelines/ompl/planner_configs/BITstar/use_k_nearest: 1
 * /move_group/planning_pipelines/ompl/planner_configs/BITstar/use_strict_queue_ordering: 0
 * /move_group/planning_pipelines/ompl/planner_configs/BKPIECE/border_fraction: 0.9
 * /move_group/planning_pipelines/ompl/planner_configs/BKPIECE/failed_expansion_score_factor: 0.5
 * /move_group/planning_pipelines/ompl/planner_configs/BKPIECE/min_valid_path_fraction: 0.5
 * /move_group/planning_pipelines/ompl/planner_configs/BKPIECE/range: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/BKPIECE/type: geometric::BKPIECE
 * /move_group/planning_pipelines/ompl/planner_configs/BiEST/range: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/BiEST/type: geometric::BiEST
 * /move_group/planning_pipelines/ompl/planner_configs/BiTRRT/cost_threshold: 1e300
 * /move_group/planning_pipelines/ompl/planner_configs/BiTRRT/frountier_node_ratio: 0.1
 * /move_group/planning_pipelines/ompl/planner_configs/BiTRRT/frountier_threshold: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/BiTRRT/init_temperature: 100
 * /move_group/planning_pipelines/ompl/planner_configs/BiTRRT/range: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/BiTRRT/temp_change_factor: 0.1
 * /move_group/planning_pipelines/ompl/planner_configs/BiTRRT/type: geometric::BiTRRT
 * /move_group/planning_pipelines/ompl/planner_configs/EST/goal_bias: 0.05
 * /move_group/planning_pipelines/ompl/planner_configs/EST/range: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/EST/type: geometric::EST
 * /move_group/planning_pipelines/ompl/planner_configs/FMT/cache_cc: 1
 * /move_group/planning_pipelines/ompl/planner_configs/FMT/extended_fmt: 1
 * /move_group/planning_pipelines/ompl/planner_configs/FMT/heuristics: 0
 * /move_group/planning_pipelines/ompl/planner_configs/FMT/nearest_k: 1
 * /move_group/planning_pipelines/ompl/planner_configs/FMT/num_samples: 1000
 * /move_group/planning_pipelines/ompl/planner_configs/FMT/radius_multiplier: 1.1
 * /move_group/planning_pipelines/ompl/planner_configs/FMT/type: geometric::FMT
 * /move_group/planning_pipelines/ompl/planner_configs/KPIECE/border_fraction: 0.9
 * /move_group/planning_pipelines/ompl/planner_configs/KPIECE/failed_expansion_score_factor: 0.5
 * /move_group/planning_pipelines/ompl/planner_configs/KPIECE/goal_bias: 0.05
 * /move_group/planning_pipelines/ompl/planner_configs/KPIECE/min_valid_path_fraction: 0.5
 * /move_group/planning_pipelines/ompl/planner_configs/KPIECE/range: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/KPIECE/type: geometric::KPIECE
 * /move_group/planning_pipelines/ompl/planner_configs/LBKPIECE/border_fraction: 0.9
 * /move_group/planning_pipelines/ompl/planner_configs/LBKPIECE/min_valid_path_fraction: 0.5
 * /move_group/planning_pipelines/ompl/planner_configs/LBKPIECE/range: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/LBKPIECE/type: geometric::LBKPIECE
 * /move_group/planning_pipelines/ompl/planner_configs/LBTRRT/epsilon: 0.4
 * /move_group/planning_pipelines/ompl/planner_configs/LBTRRT/goal_bias: 0.05
 * /move_group/planning_pipelines/ompl/planner_configs/LBTRRT/range: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/LBTRRT/type: geometric::LBTRRT
 * /move_group/planning_pipelines/ompl/planner_configs/LazyPRM/range: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/LazyPRM/type: geometric::LazyPRM
 * /move_group/planning_pipelines/ompl/planner_configs/LazyPRMstar/type: geometric::LazyPR...
 * /move_group/planning_pipelines/ompl/planner_configs/PDST/type: geometric::PDST
 * /move_group/planning_pipelines/ompl/planner_configs/PRM/max_nearest_neighbors: 10
 * /move_group/planning_pipelines/ompl/planner_configs/PRM/type: geometric::PRM
 * /move_group/planning_pipelines/ompl/planner_configs/PRMstar/type: geometric::PRMstar
 * /move_group/planning_pipelines/ompl/planner_configs/ProjEST/goal_bias: 0.05
 * /move_group/planning_pipelines/ompl/planner_configs/ProjEST/range: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/ProjEST/type: geometric::ProjEST
 * /move_group/planning_pipelines/ompl/planner_configs/RRT/goal_bias: 0.05
 * /move_group/planning_pipelines/ompl/planner_configs/RRT/range: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/RRT/type: geometric::RRT
 * /move_group/planning_pipelines/ompl/planner_configs/RRTConnect/range: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/RRTConnect/type: geometric::RRTCon...
 * /move_group/planning_pipelines/ompl/planner_configs/RRTstar/delay_collision_checking: 1
 * /move_group/planning_pipelines/ompl/planner_configs/RRTstar/goal_bias: 0.05
 * /move_group/planning_pipelines/ompl/planner_configs/RRTstar/range: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/RRTstar/type: geometric::RRTstar
 * /move_group/planning_pipelines/ompl/planner_configs/SBL/range: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/SBL/type: geometric::SBL
 * /move_group/planning_pipelines/ompl/planner_configs/SPARS/dense_delta_fraction: 0.001
 * /move_group/planning_pipelines/ompl/planner_configs/SPARS/max_failures: 1000
 * /move_group/planning_pipelines/ompl/planner_configs/SPARS/sparse_delta_fraction: 0.25
 * /move_group/planning_pipelines/ompl/planner_configs/SPARS/stretch_factor: 3.0
 * /move_group/planning_pipelines/ompl/planner_configs/SPARS/type: geometric::SPARS
 * /move_group/planning_pipelines/ompl/planner_configs/SPARStwo/dense_delta_fraction: 0.001
 * /move_group/planning_pipelines/ompl/planner_configs/SPARStwo/max_failures: 5000
 * /move_group/planning_pipelines/ompl/planner_configs/SPARStwo/sparse_delta_fraction: 0.25
 * /move_group/planning_pipelines/ompl/planner_configs/SPARStwo/stretch_factor: 3.0
 * /move_group/planning_pipelines/ompl/planner_configs/SPARStwo/type: geometric::SPARStwo
 * /move_group/planning_pipelines/ompl/planner_configs/STRIDE/degree: 16
 * /move_group/planning_pipelines/ompl/planner_configs/STRIDE/estimated_dimension: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/STRIDE/goal_bias: 0.05
 * /move_group/planning_pipelines/ompl/planner_configs/STRIDE/max_degree: 18
 * /move_group/planning_pipelines/ompl/planner_configs/STRIDE/max_pts_per_leaf: 6
 * /move_group/planning_pipelines/ompl/planner_configs/STRIDE/min_degree: 12
 * /move_group/planning_pipelines/ompl/planner_configs/STRIDE/min_valid_path_fraction: 0.2
 * /move_group/planning_pipelines/ompl/planner_configs/STRIDE/range: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/STRIDE/type: geometric::STRIDE
 * /move_group/planning_pipelines/ompl/planner_configs/STRIDE/use_projected_distance: 0
 * /move_group/planning_pipelines/ompl/planner_configs/TRRT/frountierNodeRatio: 0.1
 * /move_group/planning_pipelines/ompl/planner_configs/TRRT/frountier_threshold: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/TRRT/goal_bias: 0.05
 * /move_group/planning_pipelines/ompl/planner_configs/TRRT/init_temperature: 10e-6
 * /move_group/planning_pipelines/ompl/planner_configs/TRRT/k_constant: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/TRRT/max_states_failed: 10
 * /move_group/planning_pipelines/ompl/planner_configs/TRRT/min_temperature: 10e-10
 * /move_group/planning_pipelines/ompl/planner_configs/TRRT/range: 0.0
 * /move_group/planning_pipelines/ompl/planner_configs/TRRT/temp_change_factor: 2.0
 * /move_group/planning_pipelines/ompl/planner_configs/TRRT/type: geometric::TRRT
 * /move_group/planning_pipelines/ompl/planning_plugin: ompl_interface/OM...
 * /move_group/planning_pipelines/ompl/request_adapters: default_planner_r...
 * /move_group/planning_pipelines/ompl/start_state_max_bounds_error: 0.1
 * /move_group/planning_pipelines/pilz_industrial_motion_planner/capabilities: pilz_industrial_m...
 * /move_group/planning_pipelines/pilz_industrial_motion_planner/default_planner_config: PTP
 * /move_group/planning_pipelines/pilz_industrial_motion_planner/planning_plugin: pilz_industrial_m...
 * /move_group/planning_pipelines/pilz_industrial_motion_planner/request_adapters: 
 * /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/sense_for_plan/max_safe_path_cost: 1
 * /move_group/sensors: [{'filtered_cloud...
 * /move_group/trajectory_execution/allowed_execution_duration_scaling: 1.2
 * /move_group/trajectory_execution/allowed_goal_duration_margin: 0.5
 * /move_group/trajectory_execution/allowed_start_tolerance: 0.01
 * /name_space: wagon
 * /robot_description: <?xml version="1....
 * /robot_description_kinematics/WAM/goal_joint_tolerance: 0.0001
 * /robot_description_kinematics/WAM/goal_orientation_tolerance: 0.001
 * /robot_description_kinematics/WAM/goal_position_tolerance: 0.0001
 * /robot_description_kinematics/WAM/kinematics_solver: kdl_kinematics_pl...
 * /robot_description_kinematics/WAM/kinematics_solver_search_resolution: 0.005
 * /robot_description_kinematics/WAM/kinematics_solver_timeout: 0.005
 * /robot_description_planning/cartesian_limits/max_rot_vel: 1.57
 * /robot_description_planning/cartesian_limits/max_trans_acc: 2.25
 * /robot_description_planning/cartesian_limits/max_trans_dec: -5
 * /robot_description_planning/cartesian_limits/max_trans_vel: 1
 * /robot_description_planning/default_acceleration_scaling_factor: 0.1
 * /robot_description_planning/default_velocity_scaling_factor: 0.1
 * /robot_description_planning/joint_limits/uwarl_a_wam/base_yaw_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/base_yaw_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/base_yaw_joint/max_acceleration: 1
 * /robot_description_planning/joint_limits/uwarl_a_wam/base_yaw_joint/max_velocity: 2
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_1/dist_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_1/dist_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_1/dist_joint/max_acceleration: 0.5
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_1/dist_joint/max_velocity: 5
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_1/med_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_1/med_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_1/med_joint/max_acceleration: 0.5
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_1/med_joint/max_velocity: 5
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_1/prox_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_1/prox_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_1/prox_joint/max_acceleration: 0.5
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_1/prox_joint/max_velocity: 5
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_2/dist_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_2/dist_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_2/dist_joint/max_acceleration: 0.5
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_2/dist_joint/max_velocity: 5
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_2/med_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_2/med_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_2/med_joint/max_acceleration: 0.5
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_2/med_joint/max_velocity: 5
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_2/prox_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_2/prox_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_2/prox_joint/max_acceleration: 0.5
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_2/prox_joint/max_velocity: 5
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_3/dist_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_3/dist_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_3/dist_joint/max_acceleration: 0.5
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_3/dist_joint/max_velocity: 5
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_3/med_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_3/med_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_3/med_joint/max_acceleration: 0.5
 * /robot_description_planning/joint_limits/uwarl_a_wam/bhand/finger_3/med_joint/max_velocity: 5
 * /robot_description_planning/joint_limits/uwarl_a_wam/elbow_pitch_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/elbow_pitch_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/elbow_pitch_joint/max_acceleration: 1
 * /robot_description_planning/joint_limits/uwarl_a_wam/elbow_pitch_joint/max_velocity: 2
 * /robot_description_planning/joint_limits/uwarl_a_wam/palm_yaw_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/palm_yaw_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/palm_yaw_joint/max_acceleration: 1
 * /robot_description_planning/joint_limits/uwarl_a_wam/palm_yaw_joint/max_velocity: 2
 * /robot_description_planning/joint_limits/uwarl_a_wam/shoulder_pitch_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/shoulder_pitch_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/shoulder_pitch_joint/max_acceleration: 1
 * /robot_description_planning/joint_limits/uwarl_a_wam/shoulder_pitch_joint/max_velocity: 2
 * /robot_description_planning/joint_limits/uwarl_a_wam/shoulder_yaw_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/shoulder_yaw_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/shoulder_yaw_joint/max_acceleration: 1
 * /robot_description_planning/joint_limits/uwarl_a_wam/shoulder_yaw_joint/max_velocity: 2
 * /robot_description_planning/joint_limits/uwarl_a_wam/wrist_pitch_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/wrist_pitch_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/wrist_pitch_joint/max_acceleration: 1
 * /robot_description_planning/joint_limits/uwarl_a_wam/wrist_pitch_joint/max_velocity: 2
 * /robot_description_planning/joint_limits/uwarl_a_wam/wrist_yaw_joint/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/wrist_yaw_joint/has_velocity_limits: True
 * /robot_description_planning/joint_limits/uwarl_a_wam/wrist_yaw_joint/max_acceleration: 1
 * /robot_description_planning/joint_limits/uwarl_a_wam/wrist_yaw_joint/max_velocity: 2
 * /robot_description_semantic: <?xml version="1....
 * /rosdistro: noetic
 * /rosversion: 1.16.0
 * /source_list: ['/uwarl_a/joint_...
 * /use_sim_time: True
 * /uwarl_a/amcl/base_frame_id: uwarl_a_base_foot...
 * /uwarl_a/amcl/global_frame_id: uwarl_a_map
 * /uwarl_a/amcl/gui_publish_rate: 10.0
 * /uwarl_a/amcl/initial_pose_a: 0.0
 * /uwarl_a/amcl/initial_pose_x: 0
 * /uwarl_a/amcl/initial_pose_y: 0
 * /uwarl_a/amcl/initial_pose_z: 0.127
 * /uwarl_a/amcl/kld_err: 0.05
 * /uwarl_a/amcl/kld_z: 0.99
 * /uwarl_a/amcl/laser_lambda_short: 0.1
 * /uwarl_a/amcl/laser_likelihood_max_dist: 2.0
 * /uwarl_a/amcl/laser_max_beams: 30
 * /uwarl_a/amcl/laser_model_type: likelihood_field
 * /uwarl_a/amcl/laser_sigma_hit: 0.2
 * /uwarl_a/amcl/laser_z_hit: 0.5
 * /uwarl_a/amcl/laser_z_max: 0.05
 * /uwarl_a/amcl/laser_z_rand: 0.5
 * /uwarl_a/amcl/laser_z_short: 0.05
 * /uwarl_a/amcl/max_particles: 5000
 * /uwarl_a/amcl/min_particles: 500
 * /uwarl_a/amcl/odom_alpha1: 0.2
 * /uwarl_a/amcl/odom_alpha2: 0.2
 * /uwarl_a/amcl/odom_alpha3: 0.8
 * /uwarl_a/amcl/odom_alpha4: 0.2
 * /uwarl_a/amcl/odom_alpha5: 0.1
 * /uwarl_a/amcl/odom_frame_id: uwarl_a_odom
 * /uwarl_a/amcl/odom_model_type: omni
 * /uwarl_a/amcl/recovery_alpha_fast: 0.0
 * /uwarl_a/amcl/recovery_alpha_slow: 0.0
 * /uwarl_a/amcl/resample_interval: 1
 * /uwarl_a/amcl/transform_tolerance: 0.1
 * /uwarl_a/amcl/update_min_a: 0.5
 * /uwarl_a/amcl/update_min_d: 0.2
 * /uwarl_a/amcl/use_map_topic: False
 * /uwarl_a/bhand_joints_control/joint1/joint: uwarl_a_wam/bhand...
 * /uwarl_a/bhand_joints_control/joint1/pid/d: 0.1
 * /uwarl_a/bhand_joints_control/joint1/pid/i: 0.1
 * /uwarl_a/bhand_joints_control/joint1/pid/p: 10
 * /uwarl_a/bhand_joints_control/joint1/type: effort_controller...
 * /uwarl_a/bhand_joints_control/joint2/joint: uwarl_a_wam/bhand...
 * /uwarl_a/bhand_joints_control/joint2/pid/d: 0.1
 * /uwarl_a/bhand_joints_control/joint2/pid/i: 0.1
 * /uwarl_a/bhand_joints_control/joint2/pid/p: 10
 * /uwarl_a/bhand_joints_control/joint2/type: effort_controller...
 * /uwarl_a/bhand_joints_control/joint3/joint: uwarl_a_wam/bhand...
 * /uwarl_a/bhand_joints_control/joint3/pid/d: 0.1
 * /uwarl_a/bhand_joints_control/joint3/pid/i: 0.1
 * /uwarl_a/bhand_joints_control/joint3/pid/p: 10
 * /uwarl_a/bhand_joints_control/joint3/type: effort_controller...
 * /uwarl_a/bhand_joints_control/joint4/joint: uwarl_a_wam/bhand...
 * /uwarl_a/bhand_joints_control/joint4/pid/d: 0.1
 * /uwarl_a/bhand_joints_control/joint4/pid/i: 0.1
 * /uwarl_a/bhand_joints_control/joint4/pid/p: 10
 * /uwarl_a/bhand_joints_control/joint4/type: effort_controller...
 * /uwarl_a/bhand_joints_control/joint5/joint: uwarl_a_wam/bhand...
 * /uwarl_a/bhand_joints_control/joint5/pid/d: 0.1
 * /uwarl_a/bhand_joints_control/joint5/pid/i: 0.1
 * /uwarl_a/bhand_joints_control/joint5/pid/p: 10
 * /uwarl_a/bhand_joints_control/joint5/type: effort_controller...
 * /uwarl_a/bhand_joints_control/joint6/joint: uwarl_a_wam/bhand...
 * /uwarl_a/bhand_joints_control/joint6/pid/d: 0.1
 * /uwarl_a/bhand_joints_control/joint6/pid/i: 0.1
 * /uwarl_a/bhand_joints_control/joint6/pid/p: 10
 * /uwarl_a/bhand_joints_control/joint6/type: effort_controller...
 * /uwarl_a/bhand_joints_control/joint7/joint: uwarl_a_wam/bhand...
 * /uwarl_a/bhand_joints_control/joint7/pid/d: 0.1
 * /uwarl_a/bhand_joints_control/joint7/pid/i: 0.1
 * /uwarl_a/bhand_joints_control/joint7/pid/p: 10
 * /uwarl_a/bhand_joints_control/joint7/type: effort_controller...
 * /uwarl_a/bhand_joints_control/joint8/joint: uwarl_a_wam/bhand...
 * /uwarl_a/bhand_joints_control/joint8/pid/d: 0.1
 * /uwarl_a/bhand_joints_control/joint8/pid/i: 0.1
 * /uwarl_a/bhand_joints_control/joint8/pid/p: 10
 * /uwarl_a/bhand_joints_control/joint8/type: effort_controller...
 * /uwarl_a/bhand_joints_control/joint_state_controller/publish_rate: 50
 * /uwarl_a/bhand_joints_control/joint_state_controller/type: joint_state_contr...
 * /uwarl_a/complementary_filter_node/do_adaptive_gain: True
 * /uwarl_a/complementary_filter_node/do_bias_estimation: False
 * /uwarl_a/complementary_filter_node/fixed_frame: uwarl_a_imu_link
 * /uwarl_a/complementary_filter_node/gain_acc: 0.005
 * /uwarl_a/complementary_filter_node/gain_mag: 0.001
 * /uwarl_a/complementary_filter_node/publish_debug_topics: True
 * /uwarl_a/complementary_filter_node/publish_tf: False
 * /uwarl_a/complementary_filter_node/use_mag: False
 * /uwarl_a/controller_list: [{'name': '/eff_b...
 * /uwarl_a/eff_based_pos_traj_controller/action_monitor_rate: 20
 * /uwarl_a/eff_based_pos_traj_controller/constraints/goal_time: 10
 * /uwarl_a/eff_based_pos_traj_controller/constraints/stopped_velocity_tolerance: 0.05
 * /uwarl_a/eff_based_pos_traj_controller/constraints/uwarl_a_wam/base_yaw_joint/goal: 0.1
 * /uwarl_a/eff_based_pos_traj_controller/constraints/uwarl_a_wam/base_yaw_joint/trajectory: 0.1
 * /uwarl_a/eff_based_pos_traj_controller/constraints/uwarl_a_wam/elbow_pitch_joint/goal: 0.1
 * /uwarl_a/eff_based_pos_traj_controller/constraints/uwarl_a_wam/elbow_pitch_joint/trajectory: 0.1
 * /uwarl_a/eff_based_pos_traj_controller/constraints/uwarl_a_wam/palm_yaw_joint/goal: 0.1
 * /uwarl_a/eff_based_pos_traj_controller/constraints/uwarl_a_wam/palm_yaw_joint/trajectory: 0.1
 * /uwarl_a/eff_based_pos_traj_controller/constraints/uwarl_a_wam/shoulder_pitch_joint/goal: 0.1
 * /uwarl_a/eff_based_pos_traj_controller/constraints/uwarl_a_wam/shoulder_pitch_joint/trajectory: 0.1
 * /uwarl_a/eff_based_pos_traj_controller/constraints/uwarl_a_wam/shoulder_yaw_joint/goal: 0.1
 * /uwarl_a/eff_based_pos_traj_controller/constraints/uwarl_a_wam/shoulder_yaw_joint/trajectory: 0.1
 * /uwarl_a/eff_based_pos_traj_controller/constraints/uwarl_a_wam/wrist_pitch_joint/goal: 0.1
 * /uwarl_a/eff_based_pos_traj_controller/constraints/uwarl_a_wam/wrist_pitch_joint/trajectory: 0.1
 * /uwarl_a/eff_based_pos_traj_controller/constraints/uwarl_a_wam/wrist_yaw_joint/goal: 0.1
 * /uwarl_a/eff_based_pos_traj_controller/constraints/uwarl_a_wam/wrist_yaw_joint/trajectory: 0.1
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/base_yaw_joint/d: 10
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/base_yaw_joint/i: 2.5
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/base_yaw_joint/i_clamp: 0
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/base_yaw_joint/p: 900
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/elbow_pitch_joint/d: 2
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/elbow_pitch_joint/i: 0.5
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/elbow_pitch_joint/i_clamp: 0
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/elbow_pitch_joint/p: 500
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/palm_yaw_joint/d: 0.05
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/palm_yaw_joint/i: 0.1
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/palm_yaw_joint/i_clamp: 0
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/palm_yaw_joint/p: 8
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_pitch_joint/d: 20
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_pitch_joint/i: 5
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_pitch_joint/i_clamp: 0
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_pitch_joint/p: 2500
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_yaw_joint/d: 5
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_yaw_joint/i: 2
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_yaw_joint/i_clamp: 0
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/shoulder_yaw_joint/p: 600
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_pitch_joint/d: 0.5
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_pitch_joint/i: 0.5
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_pitch_joint/i_clamp: 0
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_pitch_joint/p: 50
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_yaw_joint/d: 0.5
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_yaw_joint/i: 0.5
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_yaw_joint/i_clamp: 0
 * /uwarl_a/eff_based_pos_traj_controller/gains/uwarl_a_wam/wrist_yaw_joint/p: 50
 * /uwarl_a/eff_based_pos_traj_controller/joints: ['uwarl_a_wam/bas...
 * /uwarl_a/eff_based_pos_traj_controller/state_publish_rate: 500
 * /uwarl_a/eff_based_pos_traj_controller/stop_trajectory_duration: 0.5
 * /uwarl_a/eff_based_pos_traj_controller/type: effort_controller...
 * /uwarl_a/generic_hw_control_loop/cycle_time_error_threshold: 0.01
 * /uwarl_a/generic_hw_control_loop/loop_hz: 300
 * /uwarl_a/hardware_interface/joints: ['uwarl_a_wam/bas...
 * /uwarl_a/hardware_interface/sim_control_mode: 0
 * /uwarl_a/joint_read_state_controller/publish_rate: 100.0
 * /uwarl_a/joint_read_state_controller/type: joint_state_contr...
 * /uwarl_a/joint_state_controller/publish_rate: 500
 * /uwarl_a/joint_state_controller/type: joint_state_contr...
 * /uwarl_a/joy/autorepeat_rate: 10.0
 * /uwarl_a/joy/deadzone: 0.12
 * /uwarl_a/joy/dev: /dev/input/js_base
 * /uwarl_a/map_server/frame_id: uwarl_a_map
 * /uwarl_a/move_base/TebLocalPlannerROS/acc_lim_theta: 0.2
 * /uwarl_a/move_base/TebLocalPlannerROS/acc_lim_x: 0.2
 * /uwarl_a/move_base/TebLocalPlannerROS/acc_lim_y: 0.2
 * /uwarl_a/move_base/TebLocalPlannerROS/allow_init_with_backwards_motion: True
 * /uwarl_a/move_base/TebLocalPlannerROS/cmd_angle_instead_rotvel: False
 * /uwarl_a/move_base/TebLocalPlannerROS/costmap_converter_plugin: costmap_converter...
 * /uwarl_a/move_base/TebLocalPlannerROS/costmap_converter_rate: 5
 * /uwarl_a/move_base/TebLocalPlannerROS/costmap_converter_spin_thread: True
 * /uwarl_a/move_base/TebLocalPlannerROS/costmap_obstacles_behind_robot_dist: 1.0
 * /uwarl_a/move_base/TebLocalPlannerROS/dt_hysteresis: 0.1
 * /uwarl_a/move_base/TebLocalPlannerROS/dt_ref: 0.3
 * /uwarl_a/move_base/TebLocalPlannerROS/enable_homotopy_class_planning: False
 * /uwarl_a/move_base/TebLocalPlannerROS/enable_multithreading: True
 * /uwarl_a/move_base/TebLocalPlannerROS/exact_arc_length: False
 * /uwarl_a/move_base/TebLocalPlannerROS/feasibility_check_no_poses: 5
 * /uwarl_a/move_base/TebLocalPlannerROS/footprint_model/type: polygon
 * /uwarl_a/move_base/TebLocalPlannerROS/footprint_model/vertices: [[0.375, -0.34], ...
 * /uwarl_a/move_base/TebLocalPlannerROS/force_reinit_new_goal_dist: 1.0
 * /uwarl_a/move_base/TebLocalPlannerROS/free_goal_vel: False
 * /uwarl_a/move_base/TebLocalPlannerROS/global_plan_overwrite_orientation: True
 * /uwarl_a/move_base/TebLocalPlannerROS/global_plan_viapoint_sep: 0.5
 * /uwarl_a/move_base/TebLocalPlannerROS/h_signature_prescaler: 1.0
 * /uwarl_a/move_base/TebLocalPlannerROS/h_signature_threshold: 0.1
 * /uwarl_a/move_base/TebLocalPlannerROS/include_costmap_obstacles: True
 * /uwarl_a/move_base/TebLocalPlannerROS/inflation_dist: 0.7
 * /uwarl_a/move_base/TebLocalPlannerROS/legacy_obstacle_association: False
 * /uwarl_a/move_base/TebLocalPlannerROS/map_frame: uwarl_a_map
 * /uwarl_a/move_base/TebLocalPlannerROS/max_global_plan_lookahead_dist: 3.0
 * /uwarl_a/move_base/TebLocalPlannerROS/max_number_classes: 4
 * /uwarl_a/move_base/TebLocalPlannerROS/max_vel_theta: 0.785
 * /uwarl_a/move_base/TebLocalPlannerROS/max_vel_x: 0.75
 * /uwarl_a/move_base/TebLocalPlannerROS/max_vel_x_backwards: 0.15
 * /uwarl_a/move_base/TebLocalPlannerROS/max_vel_y: 0.5
 * /uwarl_a/move_base/TebLocalPlannerROS/min_obstacle_dist: 0.3
 * /uwarl_a/move_base/TebLocalPlannerROS/min_samples: 3
 * /uwarl_a/move_base/TebLocalPlannerROS/min_turning_radius: 0.0
 * /uwarl_a/move_base/TebLocalPlannerROS/no_inner_iterations: 5
 * /uwarl_a/move_base/TebLocalPlannerROS/no_outer_iterations: 4
 * /uwarl_a/move_base/TebLocalPlannerROS/obstacle_association_cutoff_factor: 5.0
 * /uwarl_a/move_base/TebLocalPlannerROS/obstacle_association_force_inclusion_factor: 1.5
 * /uwarl_a/move_base/TebLocalPlannerROS/obstacle_heading_threshold: 0.45
 * /uwarl_a/move_base/TebLocalPlannerROS/obstacle_keypoint_offset: 0.1
 * /uwarl_a/move_base/TebLocalPlannerROS/obstacle_poses_affected: 30
 * /uwarl_a/move_base/TebLocalPlannerROS/odom_topic: robotnik_base_con...
 * /uwarl_a/move_base/TebLocalPlannerROS/optimization_activate: True
 * /uwarl_a/move_base/TebLocalPlannerROS/optimization_verbose: False
 * /uwarl_a/move_base/TebLocalPlannerROS/penalty_epsilon: 0.1
 * /uwarl_a/move_base/TebLocalPlannerROS/publish_feedback: False
 * /uwarl_a/move_base/TebLocalPlannerROS/roadmap_graph_area_width: 5
 * /uwarl_a/move_base/TebLocalPlannerROS/roadmap_graph_no_samples: 15
 * /uwarl_a/move_base/TebLocalPlannerROS/selection_alternative_time_cost: False
 * /uwarl_a/move_base/TebLocalPlannerROS/selection_cost_hysteresis: 1.0
 * /uwarl_a/move_base/TebLocalPlannerROS/selection_obst_cost_scale: 4.0
 * /uwarl_a/move_base/TebLocalPlannerROS/selection_viapoint_cost_scale: 1.0
 * /uwarl_a/move_base/TebLocalPlannerROS/shrink_horizon_backup: True
 * /uwarl_a/move_base/TebLocalPlannerROS/shrink_horizon_min_duration: 10
 * /uwarl_a/move_base/TebLocalPlannerROS/simple_exploration: False
 * /uwarl_a/move_base/TebLocalPlannerROS/teb_autosize: True
 * /uwarl_a/move_base/TebLocalPlannerROS/visualize_hc_graph: False
 * /uwarl_a/move_base/TebLocalPlannerROS/weight_acc_lim_theta: 1
 * /uwarl_a/move_base/TebLocalPlannerROS/weight_acc_lim_x: 1
 * /uwarl_a/move_base/TebLocalPlannerROS/weight_acc_lim_y: 1
 * /uwarl_a/move_base/TebLocalPlannerROS/weight_adapt_factor: 2
 * /uwarl_a/move_base/TebLocalPlannerROS/weight_inflation: 1
 * /uwarl_a/move_base/TebLocalPlannerROS/weight_kinematics_forward_drive: 50
 * /uwarl_a/move_base/TebLocalPlannerROS/weight_kinematics_nh: 10
 * /uwarl_a/move_base/TebLocalPlannerROS/weight_kinematics_turning_radius: 1
 * /uwarl_a/move_base/TebLocalPlannerROS/weight_max_vel_theta: 20
 * /uwarl_a/move_base/TebLocalPlannerROS/weight_max_vel_x: 20
 * /uwarl_a/move_base/TebLocalPlannerROS/weight_max_vel_y: 20
 * /uwarl_a/move_base/TebLocalPlannerROS/weight_obstacle: 50
 * /uwarl_a/move_base/TebLocalPlannerROS/weight_optimaltime: 10
 * /uwarl_a/move_base/TebLocalPlannerROS/weight_viapoint: 100
 * /uwarl_a/move_base/TebLocalPlannerROS/wheelbase: 0.0
 * /uwarl_a/move_base/TebLocalPlannerROS/xy_goal_tolerance: 0.2
 * /uwarl_a/move_base/TebLocalPlannerROS/yaw_goal_tolerance: 0.1
 * /uwarl_a/move_base/aggresive_reset/layer_names: ['obstacle_laser_...
 * /uwarl_a/move_base/aggresive_reset/reset_distance: 0.0
 * /uwarl_a/move_base/base_global_planner: global_planner/Gl...
 * /uwarl_a/move_base/base_local_planner: teb_local_planner...
 * /uwarl_a/move_base/clearing_rotation_allowed: False
 * /uwarl_a/move_base/conservative_reset/layer_names: ['obstacle_laser_...
 * /uwarl_a/move_base/conservative_reset/reset_distance: 10.0
 * /uwarl_a/move_base/conservative_reset_dist: 3.0
 * /uwarl_a/move_base/controller_frequency: 20.0
 * /uwarl_a/move_base/controller_patience: 15.0
 * /uwarl_a/move_base/global_costmap/footprint: [[0.375, -0.34], ...
 * /uwarl_a/move_base/global_costmap/global_frame: uwarl_a_map
 * /uwarl_a/move_base/global_costmap/inflation_layer/inflation_radius: 0.3
 * /uwarl_a/move_base/global_costmap/obstacle_camera_layer/front_rgbd_to_scan/clearing: True
 * /uwarl_a/move_base/global_costmap/obstacle_camera_layer/front_rgbd_to_scan/data_type: LaserScan
 * /uwarl_a/move_base/global_costmap/obstacle_camera_layer/front_rgbd_to_scan/marking: True
 * /uwarl_a/move_base/global_costmap/obstacle_camera_layer/front_rgbd_to_scan/topic: front_rgbd_camera...
 * /uwarl_a/move_base/global_costmap/obstacle_camera_layer/observation_sources: front_rgbd_to_scan
 * /uwarl_a/move_base/global_costmap/obstacle_camera_layer/obstacle_range: 2.5
 * /uwarl_a/move_base/global_costmap/obstacle_camera_layer/raytrace_range: 5.5
 * /uwarl_a/move_base/global_costmap/obstacle_laser_layer/front_laser/clearing: True
 * /uwarl_a/move_base/global_costmap/obstacle_laser_layer/front_laser/data_type: LaserScan
 * /uwarl_a/move_base/global_costmap/obstacle_laser_layer/front_laser/marking: True
 * /uwarl_a/move_base/global_costmap/obstacle_laser_layer/front_laser/topic: front_laser/scan
 * /uwarl_a/move_base/global_costmap/obstacle_laser_layer/observation_sources: front_laser rear_...
 * /uwarl_a/move_base/global_costmap/obstacle_laser_layer/obstacle_range: 2.5
 * /uwarl_a/move_base/global_costmap/obstacle_laser_layer/raytrace_range: 5.5
 * /uwarl_a/move_base/global_costmap/obstacle_laser_layer/rear_laser/clearing: True
 * /uwarl_a/move_base/global_costmap/obstacle_laser_layer/rear_laser/data_type: LaserScan
 * /uwarl_a/move_base/global_costmap/obstacle_laser_layer/rear_laser/marking: True
 * /uwarl_a/move_base/global_costmap/obstacle_laser_layer/rear_laser/topic: rear_laser/scan
 * /uwarl_a/move_base/global_costmap/plugins: [{'name': 'static...
 * /uwarl_a/move_base/global_costmap/publish_frequency: 1.0
 * /uwarl_a/move_base/global_costmap/robot_base_frame: uwarl_a_base_foot...
 * /uwarl_a/move_base/global_costmap/static_map/lethal_cost_threshold: 94
 * /uwarl_a/move_base/global_costmap/static_map/map_topic: map
 * /uwarl_a/move_base/global_costmap/static_map/static_map: True
 * /uwarl_a/move_base/global_costmap/static_map/trinary_costmap: False
 * /uwarl_a/move_base/global_costmap/static_map/unknown_cost_value: 1
 * /uwarl_a/move_base/global_costmap/static_map/use_maximum: False
 * /uwarl_a/move_base/global_costmap/update_frequency: 5.0
 * /uwarl_a/move_base/local_costmap/footprint: [[0.375, -0.34], ...
 * /uwarl_a/move_base/local_costmap/footprint_padding: 0.0
 * /uwarl_a/move_base/local_costmap/global_frame: uwarl_a_odom
 * /uwarl_a/move_base/local_costmap/height: 7.0
 * /uwarl_a/move_base/local_costmap/inflation_layer/inflation_radius: 0.3
 * /uwarl_a/move_base/local_costmap/obstacle_camera_layer/front_rgbd_to_scan/clearing: True
 * /uwarl_a/move_base/local_costmap/obstacle_camera_layer/front_rgbd_to_scan/data_type: LaserScan
 * /uwarl_a/move_base/local_costmap/obstacle_camera_layer/front_rgbd_to_scan/marking: True
 * /uwarl_a/move_base/local_costmap/obstacle_camera_layer/front_rgbd_to_scan/topic: front_rgbd_camera...
 * /uwarl_a/move_base/local_costmap/obstacle_camera_layer/observation_sources: front_rgbd_to_scan
 * /uwarl_a/move_base/local_costmap/obstacle_camera_layer/obstacle_range: 2.5
 * /uwarl_a/move_base/local_costmap/obstacle_camera_layer/raytrace_range: 5.5
 * /uwarl_a/move_base/local_costmap/obstacle_laser_layer/front_laser/clearing: True
 * /uwarl_a/move_base/local_costmap/obstacle_laser_layer/front_laser/data_type: LaserScan
 * /uwarl_a/move_base/local_costmap/obstacle_laser_layer/front_laser/marking: True
 * /uwarl_a/move_base/local_costmap/obstacle_laser_layer/front_laser/topic: front_laser/scan
 * /uwarl_a/move_base/local_costmap/obstacle_laser_layer/observation_sources: front_laser rear_...
 * /uwarl_a/move_base/local_costmap/obstacle_laser_layer/obstacle_range: 2.5
 * /uwarl_a/move_base/local_costmap/obstacle_laser_layer/raytrace_range: 5.5
 * /uwarl_a/move_base/local_costmap/obstacle_laser_layer/rear_laser/clearing: True
 * /uwarl_a/move_base/local_costmap/obstacle_laser_layer/rear_laser/data_type: LaserScan
 * /uwarl_a/move_base/local_costmap/obstacle_laser_layer/rear_laser/marking: True
 * /uwarl_a/move_base/local_costmap/obstacle_laser_layer/rear_laser/topic: rear_laser/scan
 * /uwarl_a/move_base/local_costmap/plugins: [{'name': 'obstac...
 * /uwarl_a/move_base/local_costmap/publish_frequency: 1.0
 * /uwarl_a/move_base/local_costmap/resolution: 0.05
 * /uwarl_a/move_base/local_costmap/robot_base_frame: uwarl_a_base_foot...
 * /uwarl_a/move_base/local_costmap/rolling_window: True
 * /uwarl_a/move_base/local_costmap/static_map: False
 * /uwarl_a/move_base/local_costmap/update_frequency: 5.0
 * /uwarl_a/move_base/local_costmap/width: 7.0
 * /uwarl_a/move_base/max_planning_retries: 10
 * /uwarl_a/move_base/oscillation_distance: 0.5
 * /uwarl_a/move_base/oscillation_timeout: 0.0
 * /uwarl_a/move_base/planner_frequency: 0.2
 * /uwarl_a/move_base/planner_patience: 15.0
 * /uwarl_a/move_base/recovery_behavior_enabled: True
 * /uwarl_a/move_base/recovery_behaviors: [{'name': 'conser...
 * /uwarl_a/move_base/shutdown_costmaps: False
 * /uwarl_a/robot_description: <?xml version="1....
 * /uwarl_a/robot_state_publisher/publish_frequency: 100.0
 * /uwarl_a/robotnik_base_control/angular/z/has_acceleration_limits: True
 * /uwarl_a/robotnik_base_control/angular/z/has_velocity_limits: True
 * /uwarl_a/robotnik_base_control/angular/z/max_acceleration: 6.0
 * /uwarl_a/robotnik_base_control/angular/z/max_velocity: 6.0
 * /uwarl_a/robotnik_base_control/base_frame_id: uwarl_a_base_foot...
 * /uwarl_a/robotnik_base_control/cmd_vel_timeout: 0.25
 * /uwarl_a/robotnik_base_control/enable_odom_tf: True
 * /uwarl_a/robotnik_base_control/left_wheel: ['front_left_whee...
 * /uwarl_a/robotnik_base_control/linear/x/has_acceleration_limits: True
 * /uwarl_a/robotnik_base_control/linear/x/has_velocity_limits: True
 * /uwarl_a/robotnik_base_control/linear/x/max_acceleration: 6.0
 * /uwarl_a/robotnik_base_control/linear/x/max_velocity: 3.0
 * /uwarl_a/robotnik_base_control/linear/x/min_acceleration: -6.0
 * /uwarl_a/robotnik_base_control/linear/x/min_velocity: -3.0
 * /uwarl_a/robotnik_base_control/odom_frame_id: uwarl_a_odom
 * /uwarl_a/robotnik_base_control/pose_covariance_diagonal: [0.001, 0.001, 10...
 * /uwarl_a/robotnik_base_control/publish_rate: 50.0
 * /uwarl_a/robotnik_base_control/right_wheel: ['front_right_whe...
 * /uwarl_a/robotnik_base_control/twist_covariance_diagonal: [0.001, 0.001, 10...
 * /uwarl_a/robotnik_base_control/type: diff_drive_contro...
 * /uwarl_a/robotnik_base_control/wheel_radius: 0.11
 * /uwarl_a/robotnik_base_control/wheel_radius_multiplier: 1.0
 * /uwarl_a/robotnik_base_control/wheel_separation: 0.47
 * /uwarl_a/robotnik_base_control/wheel_separation_multiplier: 1.0
 * /uwarl_a/ros_control_namespace: /
 * /uwarl_a/summit_xl_pad/axis_angular: 3
 * /uwarl_a/summit_xl_pad/axis_linear_x: 1
 * /uwarl_a/summit_xl_pad/axis_linear_y: 0
 * /uwarl_a/summit_xl_pad/axis_linear_z: 4
 * /uwarl_a/summit_xl_pad/button_bumber_override: 4
 * /uwarl_a/summit_xl_pad/button_dead_man: 5
 * /uwarl_a/summit_xl_pad/button_home: 8
 * /uwarl_a/summit_xl_pad/button_kinematic_mode: 7
 * /uwarl_a/summit_xl_pad/button_output_1: 9
 * /uwarl_a/summit_xl_pad/button_output_2: 10
 * /uwarl_a/summit_xl_pad/button_ptz_pan_left: 9
 * /uwarl_a/summit_xl_pad/button_ptz_pan_right: 9
 * /uwarl_a/summit_xl_pad/button_ptz_tilt_down: 10
 * /uwarl_a/summit_xl_pad/button_ptz_tilt_up: 10
 * /uwarl_a/summit_xl_pad/button_ptz_zoom_tele: 2
 * /uwarl_a/summit_xl_pad/button_ptz_zoom_wide: 0
 * /uwarl_a/summit_xl_pad/button_speed_down: 0
 * /uwarl_a/summit_xl_pad/button_speed_up: 3
 * /uwarl_a/summit_xl_pad/cmd_service_home: home
 * /uwarl_a/summit_xl_pad/cmd_service_io: modbus_io/write_d...
 * /uwarl_a/summit_xl_pad/cmd_service_set_mode: robotnik_base_con...
 * /uwarl_a/summit_xl_pad/cmd_topic_ptz: front_ptz_camera/...
 * /uwarl_a/summit_xl_pad/cmd_topic_vel: pad_teleop/cmd_vel
 * /uwarl_a/summit_xl_pad/joystick_dead_zone: true
 * /uwarl_a/summit_xl_pad/num_of_buttons: 13
 * /uwarl_a/summit_xl_pad/output_1: 1
 * /uwarl_a/summit_xl_pad/output_2: 2
 * /uwarl_a/summit_xl_pad/pad_type: ps4
 * /uwarl_a/summit_xl_pad/pan_increment: 0.087
 * /uwarl_a/summit_xl_pad/scale_angular: 3
 * /uwarl_a/summit_xl_pad/scale_linear: 1.5
 * /uwarl_a/summit_xl_pad/scale_linear_z: 20.0
 * /uwarl_a/summit_xl_pad/tilt_increment: 0.087
 * /uwarl_a/summit_xl_pad/zoom_increment: 300
 * /uwarl_a/twist_mux/locks: [{'name': 'e_stop...
 * /uwarl_a/twist_mux/topics: [{'name': 'pad', ...
 * /uwarl_a/wam_joints_control/joint1_position_controller/joint: uwarl_a_wam/base_...
 * /uwarl_a/wam_joints_control/joint1_position_controller/pid/d: 10.0
 * /uwarl_a/wam_joints_control/joint1_position_controller/pid/i: 2.5
 * /uwarl_a/wam_joints_control/joint1_position_controller/pid/p: 900.0
 * /uwarl_a/wam_joints_control/joint1_position_controller/type: effort_controller...
 * /uwarl_a/wam_joints_control/joint2_position_controller/joint: uwarl_a_wam/shoul...
 * /uwarl_a/wam_joints_control/joint2_position_controller/pid/d: 20.0
 * /uwarl_a/wam_joints_control/joint2_position_controller/pid/i: 5
 * /uwarl_a/wam_joints_control/joint2_position_controller/pid/p: 2500.0
 * /uwarl_a/wam_joints_control/joint2_position_controller/type: effort_controller...
 * /uwarl_a/wam_joints_control/joint3_position_controller/joint: uwarl_a_wam/shoul...
 * /uwarl_a/wam_joints_control/joint3_position_controller/pid/d: 5
 * /uwarl_a/wam_joints_control/joint3_position_controller/pid/i: 2
 * /uwarl_a/wam_joints_control/joint3_position_controller/pid/p: 600.0
 * /uwarl_a/wam_joints_control/joint3_position_controller/type: effort_controller...
 * /uwarl_a/wam_joints_control/joint4_position_controller/joint: uwarl_a_wam/elbow...
 * /uwarl_a/wam_joints_control/joint4_position_controller/pid/d: 2
 * /uwarl_a/wam_joints_control/joint4_position_controller/pid/i: 0.5
 * /uwarl_a/wam_joints_control/joint4_position_controller/pid/p: 500.0
 * /uwarl_a/wam_joints_control/joint4_position_controller/type: effort_controller...
 * /uwarl_a/wam_joints_control/joint5_position_controller/joint: uwarl_a_wam/wrist...
 * /uwarl_a/wam_joints_control/joint5_position_controller/pid/d: 0.5
 * /uwarl_a/wam_joints_control/joint5_position_controller/pid/i: 0.5
 * /uwarl_a/wam_joints_control/joint5_position_controller/pid/p: 50.0
 * /uwarl_a/wam_joints_control/joint5_position_controller/type: effort_controller...
 * /uwarl_a/wam_joints_control/joint6_position_controller/joint: uwarl_a_wam/wrist...
 * /uwarl_a/wam_joints_control/joint6_position_controller/pid/d: 0.5
 * /uwarl_a/wam_joints_control/joint6_position_controller/pid/i: 0.5
 * /uwarl_a/wam_joints_control/joint6_position_controller/pid/p: 50.0
 * /uwarl_a/wam_joints_control/joint6_position_controller/type: effort_controller...
 * /uwarl_a/wam_joints_control/joint7_position_controller/joint: uwarl_a_wam/palm_...
 * /uwarl_a/wam_joints_control/joint7_position_controller/pid/d: 0.05
 * /uwarl_a/wam_joints_control/joint7_position_controller/pid/i: 0.1
 * /uwarl_a/wam_joints_control/joint7_position_controller/pid/p: 8.0
 * /uwarl_a/wam_joints_control/joint7_position_controller/type: effort_controller...
 * /wagon/robot_description: <?xml version="1....

NODES
  /
    disable_speed_monitoring (rosservice/rosservice)
    fake_speed_override_node (prbt_hardware_support/fake_speed_override_node)
    gazebo (gazebo_ros/gzserver)
    gazebo_gui (gazebo_ros/gzclient)
    joint_state_publisher (joint_state_publisher/joint_state_publisher)
    jointmover_demo (waterloo_steel_sim_bringup/Demo_V09.py)
    move_group (moveit_ros_move_group/move_group)
    rosbag_recorder_action_server (rosbag_recorder/rosbag_recorder_server.py)
    rviz (rviz/rviz)
    rviz_arl_System_Product_Name_55514_4688502371311899189 (rviz/rviz)
  /uwarl_a/
    amcl (amcl/amcl)
    bhand_position_controller_spawner (controller_manager/spawner)
    complementary_filter_node (imu_complementary_filter/complementary_filter_node)
    controller_spawner (controller_manager/spawner)
    joy (joy/joy_node)
    map_server (map_server/map_server)
    move_base (move_base/move_base)
    pointcloud_to_laserscan (pointcloud_to_laserscan/pointcloud_to_laserscan_node)
    robot_state_publisher (robot_state_publisher/robot_state_publisher)
    summit_xl_pad (summit_xl_pad/summit_xl_pad)
    twist_marker (twist_mux/twist_marker)
    twist_mux (twist_mux/twist_mux)
    urdf_spawner_summit_model (gazebo_ros/spawn_model)
    wam_position_controller_spawner (controller_manager/spawner)
    wam_traj_position_controller_spawner (controller_manager/spawner)
  /wagon/
    joint_state_publisher (joint_state_publisher/joint_state_publisher)
    state_publisher (robot_state_publisher/robot_state_publisher)
    urdf_spawner_wagon_model (gazebo_ros/spawn_model)
    wagon_tf_publisher_action_server (wagon_tf_publisher/cart_odom.py)

auto-starting new master
process[master]: started with pid [55557]
ROS_MASTER_URI=http://localhost:11311/

setting /run_id to d45ada00-32e7-11ee-8f31-59374263d0ff
process[rosout-1]: started with pid [55574]
started core service [/rosout]
process[uwarl_a/robot_state_publisher-2]: started with pid [55581]
process[uwarl_a/urdf_spawner_summit_model-3]: started with pid [55582]
process[uwarl_a/controller_spawner-4]: started with pid [55583]
process[uwarl_a/wam_position_controller_spawner-5]: started with pid [55585]
process[uwarl_a/wam_traj_position_controller_spawner-6]: started with pid [55590]
process[uwarl_a/bhand_position_controller_spawner-7]: started with pid [55591]
process[uwarl_a/twist_mux-8]: started with pid [55593]
process[uwarl_a/twist_marker-9]: started with pid [55594]
process[uwarl_a/joy-10]: started with pid [55599]
process[uwarl_a/summit_xl_pad-11]: started with pid [55602]
process[uwarl_a/complementary_filter_node-12]: started with pid [55620]
[ERROR] [1691168179.124681095]: Couldn't open joystick /dev/input/js_base. Will retry every second.
process[uwarl_a/pointcloud_to_laserscan-13]: started with pid [55625]
process[uwarl_a/map_server-14]: started with pid [55628]
process[uwarl_a/amcl-15]: started with pid [55633]
process[uwarl_a/move_base-16]: started with pid [55637]
[ INFO] [1691168179.147116335]: Starting ComplementaryFilterROS
process[gazebo-17]: started with pid [55645]
process[gazebo_gui-18]: started with pid [55659]
process[rviz-19]: started with pid [55667]
process[wagon/joint_state_publisher-20]: started with pid [55668]
process[wagon/state_publisher-21]: started with pid [55669]
process[wagon/urdf_spawner_wagon_model-22]: started with pid [55671]
process[wagon/wagon_tf_publisher_action_server-23]: started with pid [55672]
process[rosbag_recorder_action_server-24]: started with pid [55673]
process[jointmover_demo-25]: started with pid [55685]
process[joint_state_publisher-26]: started with pid [55687]
process[move_group-27]: started with pid [55689]
[ INFO] [1691168179.225749382]: SummitXLPad num_of_buttons_ = 13, zoom = 0, 2
[ INFO] [1691168179.228843638]: bREG 0
[ INFO] [1691168179.228864587]: bREG 1
[ INFO] [1691168179.228870985]: bREG 2
[ INFO] [1691168179.228876617]: bREG 3
[ INFO] [1691168179.228882325]: bREG 4
[ INFO] [1691168179.228888188]: bREG 5
[ INFO] [1691168179.228897117]: bREG 6
[ INFO] [1691168179.228903134]: bREG 7
[ INFO] [1691168179.228908801]: bREG 8
[ INFO] [1691168179.228914685]: bREG 9
[ INFO] [1691168179.228920638]: bREG 10
[ INFO] [1691168179.228926105]: bREG 11
[ INFO] [1691168179.228931720]: bREG 12
process[rviz_arl_System_Product_Name_55514_4688502371311899189-28]: started with pid [55733]
process[fake_speed_override_node-29]: started with pid [55736]
[ WARN] [1691168179.253199126]: link 'wagon_root_link' material 'silver' undefined.
process[disable_speed_monitoring-30]: started with pid [55751]
[ WARN] [1691168179.257231589]: link 'wagon_root_link' material 'silver' undefined.
[ WARN] [1691168179.257277494]: link 'wagon_base_link' material 'silver' undefined.
[ WARN] [1691168179.257287680]: link 'wagon_base_link' material 'silver' undefined.
[ WARN] [1691168179.257315047]: link 'wagon_pocket' material 'silver' undefined.
[ WARN] [1691168179.257323301]: link 'wagon_pocket' material 'silver' undefined.
[ WARN] [1691168179.257341562]: link 'wagon_imu_link' material 'silver' undefined.
[ WARN] [1691168179.257348909]: link 'wagon_imu_link' material 'silver' undefined.
[ WARN] [1691168179.257380637]: link 'wagon_front_left_wheel_swivel_mount' material 'silver' undefined.
[ WARN] [1691168179.257389172]: link 'wagon_front_left_wheel_swivel_mount' material 'silver' undefined.
[ WARN] [1691168179.257419896]: link 'wagon_front_left_wheel' material 'silver' undefined.
[ WARN] [1691168179.257428104]: link 'wagon_front_left_wheel' material 'silver' undefined.
[ WARN] [1691168179.257456378]: link 'wagon_front_right_wheel_swivel_mount' material 'silver' undefined.
[ WARN] [1691168179.257464653]: link 'wagon_front_right_wheel_swivel_mount' material 'silver' undefined.
[ WARN] [1691168179.257491985]: link 'wagon_front_right_wheel' material 'silver' undefined.
[ WARN] [1691168179.257501321]: link 'wagon_front_right_wheel' material 'silver' undefined.
[ WARN] [1691168179.257528340]: link 'wagon_rear_left_wheel_fixed_mount' material 'silver' undefined.
[ WARN] [1691168179.257536281]: link 'wagon_rear_left_wheel_fixed_mount' material 'silver' undefined.
[ WARN] [1691168179.257562462]: link 'wagon_rear_left_wheel' material 'silver' undefined.
[ WARN] [1691168179.257569993]: link 'wagon_rear_left_wheel' material 'silver' undefined.
[ WARN] [1691168179.257596802]: link 'wagon_rear_right_wheel_fixed_mount' material 'silver' undefined.
[ WARN] [1691168179.257606719]: link 'wagon_rear_right_wheel_fixed_mount' material 'silver' undefined.
[ WARN] [1691168179.257633801]: link 'wagon_rear_right_wheel' material 'silver' undefined.
[ WARN] [1691168179.257642075]: link 'wagon_rear_right_wheel' material 'silver' undefined.
[ WARN] [1691168179.257668780]: link 'wagon_handle_1' material 'silver' undefined.
[ WARN] [1691168179.257676626]: link 'wagon_handle_1' material 'silver' undefined.
[ WARN] [1691168179.257702958]: link 'wagon_handle_2' material 'silver' undefined.
[ WARN] [1691168179.257710942]: link 'wagon_handle_2' material 'silver' undefined.
[ INFO] [1691168179.343913358]: Loading robot model 'waterloo_steel'...
[ INFO] [1691168179.350594805]: No root/virtual joint specified in SRDF. Assuming fixed joint
[ WARN] [1691168179.350686989]: Link uwarl_a_base_footprint has visual geometry but no collision geometry. Collision geometry will be left empty. Fix your URDF file by explicitly specifying collision geometry.
[ INFO] [1691168179.448125059]: rviz version 1.14.20
[ INFO] [1691168179.448315614]: compiled against Qt version 5.12.8
[ INFO] [1691168179.448348385]: compiled against OGRE version 1.9.0 (Ghadamon)
[ INFO] [1691168179.459843924]: Forcing OpenGl version 0.
[INFO] [1691168179.476138, 0.000000]: Waiting for /clock to be available...
[ INFO] [1691168179.492656300]: Requesting the map...
[INFO] [1691168179.511324, 0.000000]: Waiting for /clock to be available...
[INFO] [1691168179.574530, 0.000000]: Waiting for /clock to be available...
[INFO] [1691168179.578428, 0.000000]: /rosbag_recorder_action_server start
[INFO] [1691168179.643572, 0.000000]: Waiting for /clock to be available...
[ INFO] [1691168179.651732916]: Publishing maintained planning scene on 'monitored_planning_scene'
[ INFO] [1691168179.653094294]: Listening to 'joint_states' for joint states
[ INFO] [1691168179.655172042]: Listening to '/attached_collision_object' for attached collision objects
[ INFO] [1691168179.655201049]: Starting planning scene monitor
[ INFO] [1691168179.656159060]: Listening to '/planning_scene'
[ INFO] [1691168179.656180613]: Starting world geometry update monitor for collision objects, attached objects, octomap updates.
[ INFO] [1691168179.657200004]: Listening to '/collision_object'
[ INFO] [1691168179.659853535]: Listening to '/planning_scene_world' for planning scene world geometry
[INFO] [1691168179.687258, 0.000000]: Loading model XML from ros parameter robot_description
[INFO] [1691168179.694495, 0.000000]: Waiting for service /gazebo/spawn_urdf_model
[INFO] [1691168179.742594, 0.000000]: Loading model XML from ros parameter robot_description
[INFO] [1691168179.745908, 0.000000]: Waiting for service /gazebo/spawn_urdf_model
[ INFO] [1691168179.778739904]: Listening to '/uwarl_a/front_rgbd_camera/depth/points' using message filter with target frame 'uwarl_a_base_footprint '
[ INFO] [1691168179.778784736]: Loading planning pipeline 'chomp'
[ERROR] [1691168179.779950549]: Exception while loading planner 'chomp_interface/CHOMPPlanner': According to the loaded plugin descriptions the class chomp_interface/CHOMPPlanner with base class type planning_interface::PlannerManager does not exist. Declared types are  ompl_interface/OMPLPlanner pilz_industrial_motion_planner::CommandPlanner
Available plugins: ompl_interface/OMPLPlanner, pilz_industrial_motion_planner::CommandPlanner
[ INFO] [1691168179.781787036]: Param 'default_workspace_bounds' was not set. Using default value: 10
[ INFO] [1691168179.782032053]: Param 'start_state_max_bounds_error' was set to 0.1
[ INFO] [1691168179.782277568]: Param 'start_state_max_dt' was not set. Using default value: 0.5
[ INFO] [1691168179.782541175]: Param 'start_state_max_dt' was not set. Using default value: 0.5
[ INFO] [1691168179.782792628]: Param 'jiggle_fraction' was set to 0.05
[ INFO] [1691168179.783014069]: Param 'max_sampling_attempts' was not set. Using default value: 100
[ INFO] [1691168179.783038302]: Using planning request adapter 'Limiting Max Cartesian Speed'
[ INFO] [1691168179.783049417]: Using planning request adapter 'Add Time Parameterization'
[ INFO] [1691168179.783057093]: Using planning request adapter 'Resolve constraint frames to robot links'
[ INFO] [1691168179.783074286]: Using planning request adapter 'Fix Workspace Bounds'
[ INFO] [1691168179.783081427]: Using planning request adapter 'Fix Start State Bounds'
[ INFO] [1691168179.783087833]: Using planning request adapter 'Fix Start State In Collision'
[ INFO] [1691168179.783093661]: Using planning request adapter 'Fix Start State Path Constraints'
[ERROR] [1691168179.783712861]: Failed to initialize planning pipeline 'chomp'.
[ INFO] [1691168179.784221333]: Loading planning pipeline 'ompl'
[ INFO] [1691168179.801428560]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1691168179.802189334]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1691168179.819358851]: Using planning interface 'OMPL'
[ INFO] [1691168179.820225671]: Param 'default_workspace_bounds' was not set. Using default value: 10
[ INFO] [1691168179.820497580]: Param 'start_state_max_bounds_error' was set to 0.1
[ INFO] [1691168179.820745099]: Param 'start_state_max_dt' was not set. Using default value: 0.5
[ INFO] [1691168179.820973437]: Param 'start_state_max_dt' was not set. Using default value: 0.5
[ INFO] [1691168179.821218806]: Param 'jiggle_fraction' was set to 0.05
[ INFO] [1691168179.821460264]: Param 'max_sampling_attempts' was not set. Using default value: 100
[ INFO] [1691168179.821487978]: Using planning request adapter 'Limiting Max Cartesian Speed'
[ INFO] [1691168179.821503205]: Using planning request adapter 'Add Time Parameterization'
[ INFO] [1691168179.821518778]: Using planning request adapter 'Resolve constraint frames to robot links'
[ INFO] [1691168179.821531716]: Using planning request adapter 'Fix Workspace Bounds'
[ INFO] [1691168179.821552378]: Using planning request adapter 'Fix Start State Bounds'
[ INFO] [1691168179.821569248]: Using planning request adapter 'Fix Start State In Collision'
[ INFO] [1691168179.821586533]: Using planning request adapter 'Fix Start State Path Constraints'
[ INFO] [1691168179.822196041]: Loading planning pipeline 'pilz_industrial_motion_planner'
[ INFO] [1691168179.824140135]: Reading limits from namespace /robot_description_planning
[ INFO] [1691168179.851011295]: Available plugins: pilz_industrial_motion_planner::PlanningContextLoaderCIRC pilz_industrial_motion_planner::PlanningContextLoaderLIN pilz_industrial_motion_planner::PlanningContextLoaderPTP 
[ INFO] [1691168179.851102059]: About to load: pilz_industrial_motion_planner::PlanningContextLoaderCIRC
[ INFO] [1691168179.852218131]: Registered Algorithm [CIRC]
[ INFO] [1691168179.852288050]: About to load: pilz_industrial_motion_planner::PlanningContextLoaderLIN
[ INFO] [1691168179.853194197]: Registered Algorithm [LIN]
[ INFO] [1691168179.853244260]: About to load: pilz_industrial_motion_planner::PlanningContextLoaderPTP
[ INFO] [1691168179.854113139]: Registered Algorithm [PTP]
[ INFO] [1691168179.854163021]: Using planning interface 'Pilz Industrial Motion Planner'
[ INFO] [1691168179.932720020]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1691168179.933423147]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting...
[ INFO] [1691168181.210004991]: Stereo is NOT SUPPORTED
[ INFO] [1691168181.210045427]: OpenGL device: NVIDIA GeForce RTX 2080 Ti/PCIe/SSE2
[ INFO] [1691168181.210070573]: OpenGl version: 4.6 (GLSL 4.6).
[ INFO] [1691168181.512689738]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1691168181.525029830, 0.011000000]: Physics dynamic reconfigure ready.
[INFO] [1691168181.552063, 0.000000]: Calling service /gazebo/spawn_urdf_model
Warning [parser_urdf.cc:1130] multiple inconsistent <self_collide> exists due to fixed joint reduction overwriting previous value [1] with [0].
[INFO] [1691168181.765774, 0.149000]: Spawn status: SpawnModel: Successfully spawned entity
[ INFO] [1691168181.767141916, 0.149000000]: <robotNamespace> set to: /wagon//
[ INFO] [1691168181.767169463, 0.149000000]: <topicName> set to: imu
[ INFO] [1691168181.767178474, 0.149000000]: <frameName> set to: imu_link
[ INFO] [1691168181.767209093, 0.149000000]: <updateRateHZ> set to: 100
[ INFO] [1691168181.767220151, 0.149000000]: <gaussianNoise> set to: 0
[ INFO] [1691168181.767239458, 0.149000000]: <xyzOffset> set to: 0 0 0
[ INFO] [1691168181.767264639, 0.149000000]: <rpyOffset> set to: 0 -0 0
[INFO] [1691168181.801163, 0.179000]: Calling service /gazebo/spawn_urdf_model
[ INFO] [1691168181.823339113, 0.202000000]: Received a 4992 X 4992 map @ 0.020 m/pix

[INFO] [1691168181.840365, 0.220000]: /clock is published. Proceeding to load the controller(s).
[INFO] [1691168181.840379, 0.220000]: /clock is published. Proceeding to load the controller(s).
[INFO] [1691168181.840491, 0.220000]: /clock is published. Proceeding to load the controller(s).
[INFO] [1691168181.841445, 0.220000]: Controller Spawner: Waiting for service controller_manager/load_controller
[INFO] [1691168181.842011, 0.221000]: Controller Spawner: Waiting for service controller_manager/load_controller
[INFO] [1691168181.843076, 0.220000]: Controller Spawner: Waiting for service controller_manager/load_controller
[INFO] [1691168181.868687, 0.248000]: /clock is published. Proceeding to load the controller(s).
[INFO] [1691168181.869666, 0.248000]: Controller Spawner: Waiting for service controller_manager/load_controller
[ INFO] [1691168182.154993870, 0.350000000]: Initializing likelihood field model; this can take some time on large maps...
[wagon/urdf_spawner_wagon_model-22] process has finished cleanly
log file: /home/arnab/.ros/log/d45ada00-32e7-11ee-8f31-59374263d0ff/wagon-urdf_spawner_wagon_model-22*.log
[ INFO] [1691168183.583840922, 0.350000000]: Done initializing likelihood field model.
[ INFO] [1691168184.883656079, 0.350000000]: Loading robot model 'waterloo_steel'...
[ INFO] [1691168184.883690617, 0.350000000]: No root/virtual joint specified in SRDF. Assuming fixed joint
[ WARN] [1691168184.883741069, 0.350000000]: Link uwarl_a_base_footprint has visual geometry but no collision geometry. Collision geometry will be left empty. Fix your URDF file by explicitly specifying collision geometry.
[ INFO] [1691168185.038512623, 0.350000000]: Starting planning scene monitor
[ INFO] [1691168185.039848743, 0.350000000]: Listening to '/move_group/monitored_planning_scene'
[ INFO] [1691168185.312586810, 0.350000000]: No active joints or end effectors found for group 'BHand'. Make sure that kinematics.yaml is loaded in this node's namespace.
[ INFO] [1691168185.313092209, 0.350000000]: No active joints or end effectors found for group 'BHand'. Make sure that kinematics.yaml is loaded in this node's namespace.
[ INFO] [1691168185.319213163, 0.350000000]: waitForService: Service [/get_planning_scene] has not been advertised, waiting...
[ INFO] [1691168187.234384735, 0.350000000]: Velodyne laser plugin missing <min_range>, defaults to 0
[ INFO] [1691168187.234405654, 0.350000000]: Velodyne laser plugin missing <max_range>, defaults to infinity
[ INFO] [1691168187.234421401, 0.350000000]: Velodyne laser plugin missing <min_intensity>, defaults to no clipping
[ INFO] [1691168187.234430869, 0.350000000]: Velodyne laser plugin missing <gaussianNoise>, defaults to 0.0
[ INFO] [1691168187.235910261, 0.350000000]: Velodyne laser plugin ready, 100 lasers
[INFO] [1691168187.249180, 0.350000]: Spawn status: SpawnModel: Successfully spawned entity
[INFO] [1691168187.249998, 0.350000]: Waiting for service /gazebo/set_model_configuration
[INFO] [1691168187.251489, 0.350000]: temporary hack to **fix** the -J joint position option (issue #93), sleeping for 1 second to avoid race condition.
[ INFO] [1691168187.383967358, 0.350000000]: Camera Plugin: Using the 'robotNamespace' param: '/uwarl_a/'
[ INFO] [1691168187.384128877, 0.350000000]: Camera Plugin: Using the 'robotNamespace' param: '/uwarl_a/'
[ INFO] [1691168187.385707623, 0.350000000]: Camera Plugin (ns = /uwarl_a/)  <tf_prefix_>, set to ""
[ INFO] [1691168187.385849107, 0.350000000]: Camera Plugin (ns = /uwarl_a/)  <tf_prefix_>, set to ""
[ INFO] [1691168187.401441194, 0.350000000]: Loading gazebo_ros_control plugin
[ INFO] [1691168187.401541306, 0.350000000]: Starting gazebo_ros_control plugin in namespace: /uwarl_a/
[ INFO] [1691168187.401955560, 0.350000000]: gazebo_ros_control plugin is waiting for model URDF in parameter [/uwarl_a/robot_description] on the ROS param server.
[ERROR] [1691168187.515708737, 0.350000000]: No p gain specified for pid.  Namespace: /uwarl_a/gazebo_ros_control/pid_gains/front_right_wheel_joint
[ERROR] [1691168187.516179566, 0.350000000]: No p gain specified for pid.  Namespace: /uwarl_a/gazebo_ros_control/pid_gains/front_left_wheel_joint
[ERROR] [1691168187.516600489, 0.350000000]: No p gain specified for pid.  Namespace: /uwarl_a/gazebo_ros_control/pid_gains/back_left_wheel_joint
[ERROR] [1691168187.517029067, 0.350000000]: No p gain specified for pid.  Namespace: /uwarl_a/gazebo_ros_control/pid_gains/back_right_wheel_joint
[ INFO] [1691168187.522592654, 0.350000000]: Loaded gazebo_ros_control.
[ WARN] [1691168187.528110508, 0.350000000]: PlanarMovePlugin (ns = /uwarl_a/) missing <cmdTimeout>, defaults to -1.000000
[INFO] [1691168187.560153, 0.357000]: Controller Spawner: Waiting for service controller_manager/switch_controller
[INFO] [1691168187.560156, 0.357000]: Controller Spawner: Waiting for service controller_manager/switch_controller
[INFO] [1691168187.560948, 0.359000]: Controller Spawner: Waiting for service controller_manager/switch_controller
[INFO] [1691168187.562414, 0.360000]: Controller Spawner: Waiting for service controller_manager/unload_controller
[INFO] [1691168187.563578, 0.361000]: Controller Spawner: Waiting for service controller_manager/unload_controller
[INFO] [1691168187.564324, 0.361000]: Controller Spawner: Waiting for service controller_manager/unload_controller
[INFO] [1691168187.565556, 0.362000]: Loading controller: joint_read_state_controller
[INFO] [1691168187.567007, 0.363000]: Loading controller: bhand_joints_control/joint1
[INFO] [1691168187.568097, 0.365000]: Loading controller: eff_based_pos_traj_controller
[INFO] [1691168187.587979, 0.385000]: Controller Spawner: Waiting for service controller_manager/switch_controller
[INFO] [1691168187.589896, 0.386000]: Controller Spawner: Waiting for service controller_manager/unload_controller
[INFO] [1691168187.593033, 0.389000]: Loading controller: wam_joints_control/joint1_position_controller
[INFO] [1691168187.602309, 0.399000]: Loading controller: bhand_joints_control/joint2
[INFO] [1691168187.610530, 0.405000]: Controller Spawner: Loaded controllers: joint_read_state_controller
[INFO] [1691168187.653044, 0.428000]: Summit demo initialising...
[INFO] [1691168187.659285, 0.428000]: Waiting for action Server /uwarl_a/eff_based_pos_traj_controller/follow_joint_trajectory
[INFO] [1691168187.825340, 0.431000]: Controller Spawner: Loaded controllers: eff_based_pos_traj_controller
[INFO] [1691168187.842053, 0.448000]: Loading controller: wam_joints_control/joint2_position_controller
[INFO] [1691168187.860910, 0.467000]: Loading controller: bhand_joints_control/joint3
[INFO] [1691168187.861868, 0.468000]: Started controllers: joint_read_state_controller
[INFO] [1691168187.881189, 0.487000]: Loading controller: wam_joints_control/joint3_position_controller
[INFO] [1691168187.893040, 0.495000]: Action Server Found.../uwarl_a/eff_based_pos_traj_controller/follow_joint_trajectory
[ INFO] [1691168187.986078526, 0.495000000]: Added FollowJointTrajectory controller for /uwarl_a/eff_based_pos_traj_controller
[ INFO] [1691168187.986157621, 0.495000000]: Returned 1 controllers in list
[ INFO] [1691168187.993413318, 0.495000000]: Trajectory execution is managing controllers
[ INFO] [1691168187.993439038, 0.495000000]: MoveGroup debug mode is OFF
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'...
[ INFO] [1691168188.015557214, 0.495000000]: waitForService: Service [/get_planning_scene] is now available.
[ INFO] [1691168188.016693697, 0.495000000]: Constructing new MoveGroup connection for group 'BHand' in namespace ''
Loading 'move_group/MoveGroupPlanService'...
Loading 'move_group/MoveGroupQueryPlannersService'...
Loading 'move_group/MoveGroupStateValidationService'...
Loading 'pilz_industrial_motion_planner/MoveGroupSequenceAction'...
[ INFO] [1691168188.031017526, 0.495000000]: initialize move group sequence action
[ INFO] [1691168188.034999620, 0.495000000]: Reading limits from namespace /robot_description_planning
Loading 'pilz_industrial_motion_planner/MoveGroupSequenceService'...
[ INFO] [1691168188.060917186, 0.495000000]: Reading limits from namespace /robot_description_planning
[INFO] [1691168188.076856, 0.495000]: Loading controller: bhand_joints_control/joint4
[ INFO] [1691168188.106684873, 0.525000000]: 

********************************************************
* MoveGroup using: 
*     - ApplyPlanningSceneService
*     - ClearOctomapService
*     - CartesianPathService
*     - ExecuteTrajectoryAction
*     - GetPlanningSceneService
*     - KinematicsService
*     - MoveAction
*     - PickPlaceAction
*     - MotionPlanService
*     - QueryPlannersService
*     - StateValidationService
*     - SequenceAction
*     - SequenceService
********************************************************

[ INFO] [1691168188.107154356, 0.525000000]: MoveGroup context using planning plugin ompl_interface/OMPLPlanner
[ INFO] [1691168188.107183105, 0.525000000]: MoveGroup context initialization complete

You can start planning now!

[INFO] [1691168188.112739, 0.531000]: Loading controller: wam_joints_control/joint4_position_controller
[ WARN] [1691168188.122452752, 0.541000000]: global_costmap: Pre-Hydro parameter "static_map" unused since "plugins" is provided
[INFO] [1691168188.253159, 0.564000]: Calling service /gazebo/set_model_configuration
[INFO] [1691168188.333583, 0.564000]: Set model configuration status: SetModelConfiguration: success
[INFO] [1691168188.335275, 0.565000]: Loading controller: bhand_joints_control/joint5
[INFO] [1691168188.352428, 0.583000]: Loading controller: wam_joints_control/joint5_position_controller
[INFO] [1691168188.369351, 0.600000]: Loading controller: bhand_joints_control/joint6
[INFO] [1691168188.391516, 0.622000]: Loading controller: wam_joints_control/joint6_position_controller
[INFO] [1691168188.580568, 0.636000]: Loading controller: bhand_joints_control/joint7
[INFO] [1691168188.604447, 0.659000]: Loading controller: wam_joints_control/joint7_position_controller
[INFO] [1691168188.632276, 0.684000]: Loading controller: bhand_joints_control/joint8
[INFO] [1691168188.646567, 0.694000]: Controller Spawner: Loaded controllers: wam_joints_control/joint1_position_controller, wam_joints_control/joint2_position_controller, wam_joints_control/joint3_position_controller, wam_joints_control/joint4_position_controller, wam_joints_control/joint5_position_controller, wam_joints_control/joint6_position_controller, wam_joints_control/joint7_position_controller
[INFO] [1691168188.664417, 0.709000]: Controller Spawner: Loaded controllers: bhand_joints_control/joint1, bhand_joints_control/joint2, bhand_joints_control/joint3, bhand_joints_control/joint4, bhand_joints_control/joint5, bhand_joints_control/joint6, bhand_joints_control/joint7, bhand_joints_control/joint8
[INFO] [1691168188.665379, 0.709000]: Started controllers: wam_joints_control/joint1_position_controller, wam_joints_control/joint2_position_controller, wam_joints_control/joint3_position_controller, wam_joints_control/joint4_position_controller, wam_joints_control/joint5_position_controller, wam_joints_control/joint6_position_controller, wam_joints_control/joint7_position_controller
[INFO] [1691168188.671070, 0.715000]: Started controllers: bhand_joints_control/joint1, bhand_joints_control/joint2, bhand_joints_control/joint3, bhand_joints_control/joint4, bhand_joints_control/joint5, bhand_joints_control/joint6, bhand_joints_control/joint7, bhand_joints_control/joint8
[ WARN] [1691168188.934064044, 0.765000000]: local_costmap: Pre-Hydro parameter "static_map" unused since "plugins" is provided
[uwarl_a/urdf_spawner_summit_model-3] process has finished cleanly
log file: /home/arnab/.ros/log/d45ada00-32e7-11ee-8f31-59374263d0ff/uwarl_a-urdf_spawner_summit_model-3*.log
[ INFO] [1691168189.195861611, 0.831000000]: Ready to take commands for planning group BHand.
[INFO] [1691168190.213364, 1.064000]: Initialising WAM arm to desired position...
[INFO] [1691168190.214318, 1.065000]: Initialised WAM arm to desired position...
[INFO] [1691168190.225784, 1.075000]: Waiting for action Server /Rosbag_Recorder_as
[INFO] [1691168190.308089, 1.098000]: Action Server Found.../Rosbag_Recorder_as
[ WARN] [1691168190.408236838, 1.098000000]: Map update loop missed its desired rate of 5.0000Hz... the loop actually took 0.3330 seconds
[ INFO] [1691168190.632261231]: Subscribing to /gazebo/link_states
[ INFO] [1691168190.633668339]: Subscribing to /sequence_move_group/status
[ INFO] [1691168190.634627213]: Subscribing to /uwarl_a/joint_states
[ INFO] [1691168190.635646256]: Subscribing to /uwarl_a/robotnik_base_control/cmd_vel
[ INFO] [1691168190.636602324]: Subscribing to /uwarl_a/robotnik_base_control/odom
[ INFO] [1691168191.021128164, 1.238000000]: Recording to '/home/arnab/UWARL_catkin_ws/src/waterloo_steel/waterloo_steel_viz/waterloo_steel_sim_bringup/bagfiles/_2023-08-04-12-56-31.bag'.
[ WARN] [1691168191.884482570, 1.460000000]: Map update loop missed its desired rate of 5.0000Hz... the loop actually took 0.4950 seconds
[INFO] [1691168192.402371, 1.598000]: Switching WAM Controller to pos_trajectory controller...
ok: True
[INFO] [1691168192.408400, 1.603000]: Switched WAM Controller to pos_trajectory controller...
[jointmover_demo-25] process has finished cleanly
log file: /home/arnab/.ros/log/d45ada00-32e7-11ee-8f31-59374263d0ff/jointmover_demo-25*.log
[ WARN] [1691168206.332011158, 5.400000000]: Unable to transform object from frame 'wagon_handle_2' to planning frame 'uwarl_a_base_footprint' (Could not find a connection between 'uwarl_a_base_footprint' and 'wagon_handle_2' because they are not part of the same tree.Tf has two or more unconnected trees.)
[ WARN] [1691168206.332055489, 5.400000000]: Unable to transform object from frame 'wagon_handle_1' to planning frame 'uwarl_a_base_footprint' (Could not find a connection between 'uwarl_a_base_footprint' and 'wagon_handle_1' because they are not part of the same tree.Tf has two or more unconnected trees.)
[ WARN] [1691168206.332073380, 5.400000000]: Unable to transform object from frame 'wagon_base_link' to planning frame 'uwarl_a_base_footprint' (Could not find a connection between 'uwarl_a_base_footprint' and 'wagon_base_link' because they are not part of the same tree.Tf has two or more unconnected trees.)
[ WARN] [1691168206.332091047, 5.400000000]: Unable to transform object from frame 'wagon_front_left_wheel_swivel_mount' to planning frame 'uwarl_a_base_footprint' (Could not find a connection between 'uwarl_a_base_footprint' and 'wagon_front_left_wheel_swivel_mount' because they are not part of the same tree.Tf has two or more unconnected trees.)
[ WARN] [1691168206.332105978, 5.400000000]: Unable to transform object from frame 'wagon_front_left_wheel' to planning frame 'uwarl_a_base_footprint' (Could not find a connection between 'uwarl_a_base_footprint' and 'wagon_front_left_wheel' because they are not part of the same tree.Tf has two or more unconnected trees.)
[ WARN] [1691168206.332123709, 5.400000000]: Unable to transform object from frame 'wagon_front_right_wheel_swivel_mount' to planning frame 'uwarl_a_base_footprint' (Could not find a connection between 'uwarl_a_base_footprint' and 'wagon_front_right_wheel_swivel_mount' because they are not part of the same tree.Tf has two or more unconnected trees.)
[ WARN] [1691168206.332138491, 5.400000000]: Unable to transform object from frame 'wagon_front_right_wheel' to planning frame 'uwarl_a_base_footprint' (Could not find a connection between 'uwarl_a_base_footprint' and 'wagon_front_right_wheel' because they are not part of the same tree.Tf has two or more unconnected trees.)
[ WARN] [1691168206.332154322, 5.400000000]: Unable to transform object from frame 'wagon_rear_left_wheel' to planning frame 'uwarl_a_base_footprint' (Could not find a connection between 'uwarl_a_base_footprint' and 'wagon_rear_left_wheel' because they are not part of the same tree.Tf has two or more unconnected trees.)
[ WARN] [1691168206.332168280, 5.400000000]: Unable to transform object from frame 'wagon_rear_left_wheel_fixed_mount' to planning frame 'uwarl_a_base_footprint' (Could not find a connection between 'uwarl_a_base_footprint' and 'wagon_rear_left_wheel_fixed_mount' because they are not part of the same tree.Tf has two or more unconnected trees.)
[ WARN] [1691168206.332181780, 5.400000000]: Unable to transform object from frame 'wagon_rear_right_wheel' to planning frame 'uwarl_a_base_footprint' (Could not find a connection between 'uwarl_a_base_footprint' and 'wagon_rear_right_wheel' because they are not part of the same tree.Tf has two or more unconnected trees.)
[ WARN] [1691168206.332194950, 5.400000000]: Unable to transform object from frame 'wagon_rear_right_wheel_fixed_mount' to planning frame 'uwarl_a_base_footprint' (Could not find a connection between 'uwarl_a_base_footprint' and 'wagon_rear_right_wheel_fixed_mount' because they are not part of the same tree.Tf has two or more unconnected trees.)
[ WARN] [1691168206.332208257, 5.400000000]: Unable to transform object from frame 'wagon_imu_link' to planning frame 'uwarl_a_base_footprint' (Could not find a connection between 'uwarl_a_base_footprint' and 'wagon_imu_link' because they are not part of the same tree.Tf has two or more unconnected trees.)
[ WARN] [1691168206.332220973, 5.400000000]: Unable to transform object from frame 'wagon_pocket' to planning frame 'uwarl_a_base_footprint' (Could not find a connection between 'uwarl_a_base_footprint' and 'wagon_pocket' because they are not part of the same tree.Tf has two or more unconnected trees.)
[ WARN] [1691168206.332233926, 5.400000000]: Unable to transform object from frame 'wagon_root_link' to planning frame 'uwarl_a_base_footprint' (Could not find a connection between 'uwarl_a_base_footprint' and 'wagon_root_link' because they are not part of the same tree.Tf has two or more unconnected trees.)
[ INFO] [1691168206.332314946, 5.400000000]: Combined planning and execution request received for MoveGroupSequenceAction.
[ INFO] [1691168206.332354346, 5.400000000]: Planning attempt 1 of at most 1
[ WARN] [1691168206.332806804, 5.400000000]: Cannot find planning configuration for group 'WAM' using planner 'PTP'. Will use defaults instead.
[ INFO] [1691168206.333935541, 5.402000000]: Planner configuration 'WAM' will use planner 'geometric::RRTConnect'. Additional configuration parameters will be set when the planner is constructed.
[ INFO] [1691168206.334296012, 5.402000000]: WAM/WAM: Starting planning with 1 states already in datastructure
[ INFO] [1691168206.345775738, 5.414000000]: WAM/WAM: Created 4 states (2 start + 2 goal)
[ INFO] [1691168206.345804028, 5.414000000]: Solution found in 0.011628 seconds
[ INFO] [1691168206.355387407, 5.423000000]: SimpleSetup: Path simplification took 0.009500 seconds and changed from 3 to 2 states
[ WARN] [1691168223.927022414, 10.321000000]: Controller '/uwarl_a/eff_based_pos_traj_controller' failed with error PATH_TOLERANCE_VIOLATED: uwarl_a_wam/shoulder_yaw_joint path error 0.100017
[ WARN] [1691168223.927090405, 10.321000000]: Controller handle /uwarl_a/eff_based_pos_traj_controller reports status ABORTED
[ INFO] [1691168223.927122480, 10.321000000]: Completed trajectory execution with status ABORTED ...

Asked by chiku00 on 2023-08-04 12:19:35 UTC

Comments

Answers