GithubHelp home page GithubHelp logo

justagist / panda_simulator Goto Github PK

View Code? Open in Web Editor NEW
180.0 10.0 57.0 51.15 MB

A Gazebo simulator for the Franka Emika Panda robot with ROS interface, supporting sim-to-real code transfer (Python). Exposes customisable controllers and state feedback from robot in simulation.

License: Apache License 2.0

CMake 2.28% C++ 58.44% Objective-C 5.88% Python 32.13% Shell 0.84% Dockerfile 0.44%
gazebo-robot franka-emika franka-simulator franka-gazebo panda-gazebo panda-simulator franka-ros panda-simulation franka-simulation sim-to-real

panda_simulator's Introduction

Panda Simulator Release ROS Version Python 3.6+ Build Status

franka_ros_version franka_ros_interface_version

A Gazebo simulator for the Franka Emika Panda robot with ROS interface, providing exposed controllers and real-time robot state feedback similar to the real robot when using the Franka ROS Interface package.

Features

  • Customisable low-level controllers (joint position, velocity, torque) available that can be controlled through ROS topics (including position control for gripper) or Python API.
  • Real-time robot state (end-effector state, joint state, controller state, etc.) available through ROS topics.
  • The Franka ROS Interface package (which is a ROS interface for controlling the real Panda robot) can also be used with the panda_simulator, providing direct sim-to-real code transfer. The PandaRobot package which provides simplified python API for the robot can also be used for direct sim-to-real code transfer, as well as for performing real-time kinematics and dynamics computation.
  • Supports MoveIt planning and control for Franka Panda Emika robot arm and Franka Gripper, as well as smooth motion control using customisable ROS JointTrajectoryAction service.

For a simple bare-bone Gazebo simulator created using inbuilt Gazebo ROS controllers and transmission interfaces, see Gazebo Panda.

See version log for details about new feature updates.

Control and Monitor robot using Python API

Python API: Franka ROS Interface, PandaRobot

vid Watch video here

vid Watch video here

Control using MoveIt

vid Watch video here

Installation

ROS Melodic (noetic-devel branch): Build Status

ROS Melodic (melodic-devel branch): Build Status

ROS Kinetic (kinetic-devel branch; not maintained): Build Status

Dependencies

  • pip install -r requirements.txt #(to install numpy and numpy-quaternion) (or pip3 install -r requirements.txt)
  • libfranka (apt install ros-${ROS_DISTRO}-libfranka or install from source).
  • Most of the other basic dependencies can be met by running the following apt-get command: apt install ros-$ROS_DISTRO-gazebo-ros-control ros-${ROS_DISTRO}-rospy-message-converter ros-${ROS_DISTRO}-effort-controllers ros-${ROS_DISTRO}-joint-state-controller ros-${ROS_DISTRO}-moveit ros-${ROS_DISTRO}-moveit-commander ros-${ROS_DISTRO}-moveit-visual-tools.

The following dependencies can be installed using the .rosinstall file (instructions in next section: Building the Package).

NOTE: The franka_panda_description package above has to be independently updated regularly (using git pull) to get the latest robot description, visual and dynamics parameters.

Building the Package

1.Clone the repo:

    cd <catkin_ws>/src
    git clone -b noetic-devel https://github.com/justagist/panda_simulator

Steps 2 and 3 can be automated by running ./build_ws.sh from <catkin_ws>/src/panda_simulator.

2.Update dependency packages:

    wstool init
    wstool merge panda_simulator/dependencies.rosinstall
    wstool up

    # use old ros-compatible version of kdl
    cd orocos_kinematics_dynamics && rm -rf * && git checkout b35c424e && git reset --hard
    cd ../.. && rosdep install -y --from-paths src --ignore-src --rosdistro $ROS_DISTRO --skip-keys python-sip

3.Once the dependencies are met, the package can be installed using catkin_make:

    source /opt/ros/$ROS_DISTRO/setup.bash
    catkin build # if catkin not found, install catkin tools (apt install python-catkin-tools)
    source devel/setup.bash

Docker Build (experimental!)

Requires nvidia-docker. Gazebo and RViz may not work without nvidia-docker.

  • To build the docker image of the package, run docker build docker/ -t ps_${ROS_DISTRO}:v1.0.0, or pull built image from github (docker pull docker.pkg.github.com/justagist/panda_simulator/ps_${ROS_DISTRO}:v1.0.0). Note: Even when using the docker image, this repository has to be cloned on to the host machine.
  • To run the built image interactively, run the script ./run_docker.sh from the cloned repository. The container starts in a catkin workspace (directory location in host machine: $HOME/.panda_sim_${ROS_DISTRO}_ws). The host's home directory is also mounted in the container for access to .ros/ and for making the catkin workspace writable. To see and modify other mounted volumes, go through the run_docker.sh file.
  • When running for the first time, the catkin workspace has to be built (cd src/panda_simulator && ./build_ws.sh).
  • If everything was successfully built in the previous step, you should be able to run the simulator (see Usage section below).

Any edits made to the host directory will be reflected in the docker container (and vice-versa). You can also run and build other ROS nodes and packages without having any ROS installation on the host machine.

Usage

The simulator can be started by running:

    roslaunch panda_gazebo panda_world.launch # (use argument load_gripper:=false for starting without gripper; see other available arguments in launch file)

This exposes a variety of ROS topics and services for communicating with and controlling the robot in simulation. The robot can also be controlled using the Franka ROS Interface package and/or PandaRobot APIs.

Update: The above roslaunch command does not start the moveit server automatically anymore. If using Panda Simulator in ROS Melodic environment, the moveit server now has to be started manually by running the following command in a new terminal:

    roslaunch panda_sim_moveit sim_move_group.launch # (use argument load_gripper:=false for starting without gripper

For known errors and issues, please see Issues section below.

Demos

To run these demos, launch the simulator first: roslaunch panda_gazebo panda_world.launch. The following demos can then be tested:

  • Moveit Demo: The moveit server must be running (see usage). Run roslaunch panda_simulator_examples demo_moveit.launch to run a demo for testing the moveit planner interface with the simulated robot. This script starts a moveit RViz GUI for motion planning and terminal interface for modifying planning scene.

  • Task-space control using Franka ROS Interface (or PandaRobot) API: Run roslaunch panda_simulator_examples demo_task_space_control.launch to run a demo showing the task-space control. By default, the demo uses the (Franka ROS Interface) API to retrieve state information, and to control it using torque control (see script).

  • Task-space control using ROS topics directly: Another script demonstrating the same functionality without using the Franka ROS Interface API, and only the ROS topics from the simulation is also provided. This can be run interactively by running roslaunch panda_simulator_examples demo_task_space_control.launch use_fri:=False.

  • API usage demo: Another (much simpler) demo 'move_robot.py' is provided demonstrating (i) controlling the robot in the joint space, (ii) retrieving state information of the robot.

Task-space Impedance Control Demo

vid Watch video here

Some useful ROS topics

Published Topics
ROS Topic Data
/panda_simulator/custom_franka_state_controller/robot_state gravity, coriolis, jacobian, cartesian velocity, etc.
/panda_simulator/custom_franka_state_controller/tip_state end-effector pose, wrench, etc.
/panda_simulator/joint_states joint positions, velocities, efforts
Subscribed Topics
ROS Topic Data
/panda_simulator/motion_controller/arm/joint_commands command the robot using the currently active controller
/panda_simulator/franka_gripper/move (action msg) command the joints of the gripper

Other topics for changing the controller gains (also dynamically configurable), command timeout, etc. are also available.

ROS Services

Controller manager service can be used to switch between all available controllers (joint position, velocity, effort). Gripper joints can be controlled using the ROS ActionClient (via the same topics as the real robot and franka_ros).

Known Issues

  1. [ERROR] Exception while loading planning adapter plugin 'default_planner_request_adapters/ResolveConstraintFrames in melodic. This can be safely ignored.

  2. Error in REST request error message when starting Gazebo. This also can be safely ignored, or fixed by following the instructions here.

  3. Gripper control and model definition is not completely developed, and gripper control may not produce the required performance. Update: robot and gripper model definitions have now been improved in the franka_panda_description package.

  4. Gravity compensation when using velocity or torque controller with gripper is not very good. This is bypassed by deactivating simulator gravity by default (see panda.world).

Version Update

Check versionLog.md.

Related Packages

  • Franka ROS Interface : A ROS API for controlling and managing the Franka Emika Panda robot (real and simulated). Contains controllers for the robot (joint position, velocity, torque), interfaces for the gripper, controller manager, coordinate frames interface, etc.. Provides almost complete sim-to-real transfer of code.
  • PandaRobot : Python interface providing higher-level control of the robot integrated with its gripper, controller manager, coordinate frames manager, etc. It also provides access to the kinematics and dynamics of the robot using the KDL library.
  • Gazebo Panda: A simple bare-bone gazebo simulator using in-built gazebo controllers and transmissions. No custom controllers or interfaces.

The Franka ROS Interface package provides Python API and interface tools to control and communicate with the robot using the ROS topics and services exposed by the simulator. Since the simulator exposes similar information and controllers as the robot_state_controller_node of the Franka ROS Interface, the API can be used to control both the real robot, and the simulated robot in this package, with minimum change in code.

License

License

Copyright (c) 2019-2021, Saif Sidhik

If you use this software, please cite it using DOI.

panda_simulator's People

Contributors

justagist avatar smihael avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

panda_simulator's Issues

Incompatible with latest version of numpy-quaternion

The setup bash script installs the latest version of quaternion (currently 2021.3.11.10.32.22). The resulting error occurs when trying to start one of the demo scripts. I resolved the error for myself by using a version numpy-quaternion==2018.10.1.15.39.8.

image

gzserver: symbol lookup error:

Hello,

I pulled the docker image and built it.

After running roslaunch panda_gazebo panda_world.launch,

I am getting libgazebo_common.so.9: undefined symbol error.

I also upgrade libignition math sudo apt upgrade libignition-math2

Short LOG

gzserver: symbol lookup error: /home/erdi/.local/lib/libgazebo_common.so.9: undefined symbol: _ZN8ignition10fuel_tools12ClientConfig12SetUserAgentERKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEE
process[base_to_link0-5]: started with pid [15327]
gzclient: symbol lookup error: /home/erdi/.local/lib/libgazebo_common.so.9: undefined symbol: _ZN8ignition10fuel_tools12ClientConfig12SetUserAgentERKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEE
No handlers could be found for logger "roslaunch"
[gazebo-2] process has died [pid 15280, exit code 127, cmd /opt/ros/melodic/lib/gazebo_ros/gzserver -e ode /home/erdi/panda_sim_ws/src/panda_simulator/panda_gazebo/worlds/panda.world __name:=gazebo __log:=/home/erdi/.ros/log/5e628c3c-10bf-11eb-ab11-ccd9ac1b6b7e/gazebo-2.log].
log file: /home/erdi/.ros/log/5e628c3c-10bf-11eb-ab11-ccd9ac1b6b7e/gazebo-2*.log
[gazebo_gui-3] process has died [pid 15284, exit code 127, cmd /opt/ros/melodic/lib/gazebo_ros/gzclient __name:=gazebo_gui __log:=/home/erdi/.ros/log/5e628c3c-10bf-11eb-ab11-ccd9ac1b6b7e/gazebo_gui-3.log].
log file: /home/erdi/.ros/log/5e628c3c-10bf-11eb-ab11-ccd9ac1b6b7e/gazebo_gui-3*.log

Screenshot from 2020-10-17 23-31-23

Whole LOG Data

erdi@erdi:~/panda_sim_ws$ roslaunch panda_gazebo panda_world.launch
WARNING: Could not change permissions for folder [/home/erdi/.ros/log/5e628c3c-10bf-11eb-ab11-ccd9ac1b6b7e], make sure that the parent folder has correct permissions.
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

xacro: in-order processing became default in ROS Melodic. You can drop the option.
started roslaunch server http://localhost:43953/
SUMMARY
PARAMETERS

  • /SIMULATOR_: True
  • /arm/gravity_tip_name: panda_hand
  • /arm/root_name: panda_link0
  • /arm/tip_name: panda_hand
  • /controllers_config/default_controller: panda_simulator/p...
  • /controllers_config/position_controller: panda_simulator/p...
  • /controllers_config/torque_controller: panda_simulator/e...
  • /controllers_config/velocity_controller: panda_simulator/v...
  • /franka_gripper/robot_ip: sim
  • /gazebo/enable_ros_network: True
  • /gripper_config/default_grasp_epsilon/inner: 0.005
  • /gripper_config/default_grasp_epsilon/outer: 0.005
  • /gripper_config/default_speed: 0.1
  • /gripper_config/joint_names: ['panda_finger_jo...
  • /move_group/allow_trajectory_execution: True
  • /move_group/controller_list: [{'default': True...
  • /move_group/hand/planner_configs: ['SBLkConfigDefau...
  • /move_group/jiggle_fraction: 0.05
  • /move_group/max_range: 5.0
  • /move_group/max_safe_path_cost: 1
  • /move_group/moveit_controller_manager: moveit_simple_con...
  • /move_group/moveit_manage_controllers: True
  • /move_group/octomap_frame: camera_rgb_optica...
  • /move_group/octomap_resolution: 0.05
  • /move_group/panda_arm/planner_configs: ['SBLkConfigDefau...
  • /move_group/panda_arm_hand/planner_configs: ['SBLkConfigDefau...
  • /move_group/planner_configs/BFMTkConfigDefault/balanced: 0
  • /move_group/planner_configs/BFMTkConfigDefault/cache_cc: 1
  • /move_group/planner_configs/BFMTkConfigDefault/extended_fmt: 1
  • /move_group/planner_configs/BFMTkConfigDefault/heuristics: 1
  • /move_group/planner_configs/BFMTkConfigDefault/nearest_k: 1
  • /move_group/planner_configs/BFMTkConfigDefault/num_samples: 1000
  • /move_group/planner_configs/BFMTkConfigDefault/optimality: 1
  • /move_group/planner_configs/BFMTkConfigDefault/radius_multiplier: 1.0
  • /move_group/planner_configs/BFMTkConfigDefault/type: geometric::BFMT
  • /move_group/planner_configs/BKPIECEkConfigDefault/border_fraction: 0.9
  • /move_group/planner_configs/BKPIECEkConfigDefault/failed_expansion_score_factor: 0.5
  • /move_group/planner_configs/BKPIECEkConfigDefault/min_valid_path_fraction: 0.5
  • /move_group/planner_configs/BKPIECEkConfigDefault/range: 0.0
  • /move_group/planner_configs/BKPIECEkConfigDefault/type: geometric::BKPIECE
  • /move_group/planner_configs/BiESTkConfigDefault/range: 0.0
  • /move_group/planner_configs/BiESTkConfigDefault/type: geometric::BiEST
  • /move_group/planner_configs/BiTRRTkConfigDefault/cost_threshold: 1e300
  • /move_group/planner_configs/BiTRRTkConfigDefault/frountier_node_ratio: 0.1
  • /move_group/planner_configs/BiTRRTkConfigDefault/frountier_threshold: 0.0
  • /move_group/planner_configs/BiTRRTkConfigDefault/init_temperature: 100
  • /move_group/planner_configs/BiTRRTkConfigDefault/range: 0.0
  • /move_group/planner_configs/BiTRRTkConfigDefault/temp_change_factor: 0.1
  • /move_group/planner_configs/BiTRRTkConfigDefault/type: geometric::BiTRRT
  • /move_group/planner_configs/ESTkConfigDefault/goal_bias: 0.05
  • /move_group/planner_configs/ESTkConfigDefault/range: 0.0
  • /move_group/planner_configs/ESTkConfigDefault/type: geometric::EST
  • /move_group/planner_configs/FMTkConfigDefault/cache_cc: 1
  • /move_group/planner_configs/FMTkConfigDefault/extended_fmt: 1
  • /move_group/planner_configs/FMTkConfigDefault/heuristics: 0
  • /move_group/planner_configs/FMTkConfigDefault/nearest_k: 1
  • /move_group/planner_configs/FMTkConfigDefault/num_samples: 1000
  • /move_group/planner_configs/FMTkConfigDefault/radius_multiplier: 1.1
  • /move_group/planner_configs/FMTkConfigDefault/type: geometric::FMT
  • /move_group/planner_configs/KPIECEkConfigDefault/border_fraction: 0.9
  • /move_group/planner_configs/KPIECEkConfigDefault/failed_expansion_score_factor: 0.5
  • /move_group/planner_configs/KPIECEkConfigDefault/goal_bias: 0.05
  • /move_group/planner_configs/KPIECEkConfigDefault/min_valid_path_fraction: 0.5
  • /move_group/planner_configs/KPIECEkConfigDefault/range: 0.0
  • /move_group/planner_configs/KPIECEkConfigDefault/type: geometric::KPIECE
  • /move_group/planner_configs/LBKPIECEkConfigDefault/border_fraction: 0.9
  • /move_group/planner_configs/LBKPIECEkConfigDefault/min_valid_path_fraction: 0.5
  • /move_group/planner_configs/LBKPIECEkConfigDefault/range: 0.0
  • /move_group/planner_configs/LBKPIECEkConfigDefault/type: geometric::LBKPIECE
  • /move_group/planner_configs/LBTRRTkConfigDefault/epsilon: 0.4
  • /move_group/planner_configs/LBTRRTkConfigDefault/goal_bias: 0.05
  • /move_group/planner_configs/LBTRRTkConfigDefault/range: 0.0
  • /move_group/planner_configs/LBTRRTkConfigDefault/type: geometric::LBTRRT
  • /move_group/planner_configs/LazyPRMkConfigDefault/range: 0.0
  • /move_group/planner_configs/LazyPRMkConfigDefault/type: geometric::LazyPRM
  • /move_group/planner_configs/LazyPRMstarkConfigDefault/type: geometric::LazyPR...
  • /move_group/planner_configs/PDSTkConfigDefault/type: geometric::PDST
  • /move_group/planner_configs/PRMkConfigDefault/max_nearest_neighbors: 10
  • /move_group/planner_configs/PRMkConfigDefault/type: geometric::PRM
  • /move_group/planner_configs/PRMstarkConfigDefault/type: geometric::PRMstar
  • /move_group/planner_configs/ProjESTkConfigDefault/goal_bias: 0.05
  • /move_group/planner_configs/ProjESTkConfigDefault/range: 0.0
  • /move_group/planner_configs/ProjESTkConfigDefault/type: geometric::ProjEST
  • /move_group/planner_configs/RRTConnectkConfigDefault/range: 0.0
  • /move_group/planner_configs/RRTConnectkConfigDefault/type: geometric::RRTCon...
  • /move_group/planner_configs/RRTkConfigDefault/goal_bias: 0.05
  • /move_group/planner_configs/RRTkConfigDefault/range: 0.0
  • /move_group/planner_configs/RRTkConfigDefault/type: geometric::RRT
  • /move_group/planner_configs/RRTstarkConfigDefault/delay_collision_checking: 1
  • /move_group/planner_configs/RRTstarkConfigDefault/goal_bias: 0.05
  • /move_group/planner_configs/RRTstarkConfigDefault/range: 0.0
  • /move_group/planner_configs/RRTstarkConfigDefault/type: geometric::RRTstar
  • /move_group/planner_configs/SBLkConfigDefault/range: 0.0
  • /move_group/planner_configs/SBLkConfigDefault/type: geometric::SBL
  • /move_group/planner_configs/SPARSkConfigDefault/dense_delta_fraction: 0.001
  • /move_group/planner_configs/SPARSkConfigDefault/max_failures: 1000
  • /move_group/planner_configs/SPARSkConfigDefault/sparse_delta_fraction: 0.25
  • /move_group/planner_configs/SPARSkConfigDefault/stretch_factor: 3.0
  • /move_group/planner_configs/SPARSkConfigDefault/type: geometric::SPARS
  • /move_group/planner_configs/SPARStwokConfigDefault/dense_delta_fraction: 0.001
  • /move_group/planner_configs/SPARStwokConfigDefault/max_failures: 5000
  • /move_group/planner_configs/SPARStwokConfigDefault/sparse_delta_fraction: 0.25
  • /move_group/planner_configs/SPARStwokConfigDefault/stretch_factor: 3.0
  • /move_group/planner_configs/SPARStwokConfigDefault/type: geometric::SPARStwo
  • /move_group/planner_configs/STRIDEkConfigDefault/degree: 16
  • /move_group/planner_configs/STRIDEkConfigDefault/estimated_dimension: 0.0
  • /move_group/planner_configs/STRIDEkConfigDefault/goal_bias: 0.05
  • /move_group/planner_configs/STRIDEkConfigDefault/max_degree: 18
  • /move_group/planner_configs/STRIDEkConfigDefault/max_pts_per_leaf: 6
  • /move_group/planner_configs/STRIDEkConfigDefault/min_degree: 12
  • /move_group/planner_configs/STRIDEkConfigDefault/min_valid_path_fraction: 0.2
  • /move_group/planner_configs/STRIDEkConfigDefault/range: 0.0
  • /move_group/planner_configs/STRIDEkConfigDefault/type: geometric::STRIDE
  • /move_group/planner_configs/STRIDEkConfigDefault/use_projected_distance: 0
  • /move_group/planner_configs/TRRTkConfigDefault/frountierNodeRatio: 0.1
  • /move_group/planner_configs/TRRTkConfigDefault/frountier_threshold: 0.0
  • /move_group/planner_configs/TRRTkConfigDefault/goal_bias: 0.05
  • /move_group/planner_configs/TRRTkConfigDefault/init_temperature: 10e-6
  • /move_group/planner_configs/TRRTkConfigDefault/k_constant: 0.0
  • /move_group/planner_configs/TRRTkConfigDefault/max_states_failed: 10
  • /move_group/planner_configs/TRRTkConfigDefault/min_temperature: 10e-10
  • /move_group/planner_configs/TRRTkConfigDefault/range: 0.0
  • /move_group/planner_configs/TRRTkConfigDefault/temp_change_factor: 2.0
  • /move_group/planner_configs/TRRTkConfigDefault/type: geometric::TRRT
  • /move_group/planner_configs/TrajOptDefault/type: geometric::TrajOpt
  • /move_group/planning_plugin: ompl_interface/OM...
  • /move_group/planning_scene_monitor/publish_geometry_updates: True
  • /move_group/planning_scene_monitor/publish_planning_scene: True
  • /move_group/planning_scene_monitor/publish_state_updates: True
  • /move_group/planning_scene_monitor/publish_transforms_updates: True
  • /move_group/request_adapters: default_planner_r...
  • /move_group/sensors: [{'point_subsampl...
  • /move_group/start_state_max_bounds_error: 0.1
  • /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
  • /panda_simulator/effort_joint_gravity_controller/joints/panda_joint1_controller/joint: panda_joint1
  • /panda_simulator/effort_joint_gravity_controller/joints/panda_joint2_controller/joint: panda_joint2
  • /panda_simulator/effort_joint_gravity_controller/joints/panda_joint3_controller/joint: panda_joint3
  • /panda_simulator/effort_joint_gravity_controller/joints/panda_joint4_controller/joint: panda_joint4
  • /panda_simulator/effort_joint_gravity_controller/joints/panda_joint5_controller/joint: panda_joint5
  • /panda_simulator/effort_joint_gravity_controller/joints/panda_joint6_controller/joint: panda_joint6
  • /panda_simulator/effort_joint_gravity_controller/joints/panda_joint7_controller/joint: panda_joint7
  • /panda_simulator/effort_joint_gravity_controller/type: panda_sim_control...
  • /panda_simulator/effort_joint_torque_controller/joints/panda_joint1_controller/joint: panda_joint1
  • /panda_simulator/effort_joint_torque_controller/joints/panda_joint2_controller/joint: panda_joint2
  • /panda_simulator/effort_joint_torque_controller/joints/panda_joint3_controller/joint: panda_joint3
  • /panda_simulator/effort_joint_torque_controller/joints/panda_joint4_controller/joint: panda_joint4
  • /panda_simulator/effort_joint_torque_controller/joints/panda_joint5_controller/joint: panda_joint5
  • /panda_simulator/effort_joint_torque_controller/joints/panda_joint6_controller/joint: panda_joint6
  • /panda_simulator/effort_joint_torque_controller/joints/panda_joint7_controller/joint: panda_joint7
  • /panda_simulator/effort_joint_torque_controller/topic: /panda_simulator/...
  • /panda_simulator/effort_joint_torque_controller/type: panda_sim_control...
  • /panda_simulator/joint_state_controller/publish_rate: 100
  • /panda_simulator/joint_state_controller/type: joint_state_contr...
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/joint: panda_finger_joint1
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/d: 0.5
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/i: 50
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/p: 5000
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/joint: panda_finger_joint2
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/d: 0.5
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/i: 50
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/p: 5000
  • /panda_simulator/panda_gripper_controller/pub_topic: /franka_gripper/j...
  • /panda_simulator/panda_gripper_controller/type: panda_sim_control...
  • /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/joint: panda_joint1
  • /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/d: 25.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/i: 10.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/p: 3000
  • /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/joint: panda_joint2
  • /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/d: 30.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/i: 10.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/p: 3000
  • /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/joint: panda_joint3
  • /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/d: 30.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/i: 10.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/p: 3000
  • /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/joint: panda_joint4
  • /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/d: 50.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/i: 10.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/p: 3000
  • /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/joint: panda_joint5
  • /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/d: 8.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/i: 10.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/p: 3000
  • /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/joint: panda_joint6
  • /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/d: 5.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/i: 1.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/p: 3000
  • /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/joint: panda_joint7
  • /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/d: 4.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/i: 10.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/p: 3000
  • /panda_simulator/position_joint_position_controller/topic_joint_command: /panda_simulator/...
  • /panda_simulator/position_joint_position_controller/topic_set_speed_ratio: /panda_simulator/...
  • /panda_simulator/position_joint_position_controller/type: panda_sim_control...
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/joint: panda_joint1
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/d: 0.1
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/i: 0.0
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/p: 10
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/joint: panda_joint2
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/d: 0.1
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/i: 1.0
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/p: 100
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/joint: panda_joint3
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/d: 0.01
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/i: 0.0
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/p: 0.05
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/joint: panda_joint4
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/d: 0.1
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/i: 0.01
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/p: 0.5
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/joint: panda_joint5
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/d: 0.01
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/i: 0.0
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/p: 1.0
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/joint: panda_joint6
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/d: 0.01
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/i: 0.0
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/p: 0.05
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/joint: panda_joint7
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/d: 0.01
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/i: 0.0
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/p: 0.05
  • /panda_simulator/velocity_joint_velocity_controller/topic: /panda_simulator/...
  • /panda_simulator/velocity_joint_velocity_controller/type: panda_sim_control...
  • /robot_config/arm_id: panda
  • /robot_config/joint_config/joint_acceleration_limit/panda_joint1: 15.0
  • /robot_config/joint_config/joint_acceleration_limit/panda_joint2: 7.5
  • /robot_config/joint_config/joint_acceleration_limit/panda_joint3: 10.0
  • /robot_config/joint_config/joint_acceleration_limit/panda_joint4: 12.5
  • /robot_config/joint_config/joint_acceleration_limit/panda_joint5: 15.0
  • /robot_config/joint_config/joint_acceleration_limit/panda_joint6: 20.0
  • /robot_config/joint_config/joint_acceleration_limit/panda_joint7: 20.0
  • /robot_config/joint_config/joint_effort_limit/panda_joint1: 87
  • /robot_config/joint_config/joint_effort_limit/panda_joint2: 87
  • /robot_config/joint_config/joint_effort_limit/panda_joint3: 87
  • /robot_config/joint_config/joint_effort_limit/panda_joint4: 87
  • /robot_config/joint_config/joint_effort_limit/panda_joint5: 12
  • /robot_config/joint_config/joint_effort_limit/panda_joint6: 12
  • /robot_config/joint_config/joint_effort_limit/panda_joint7: 12
  • /robot_config/joint_config/joint_position_limit/lower/panda_joint1: -2.8973
  • /robot_config/joint_config/joint_position_limit/lower/panda_joint2: -1.7628
  • /robot_config/joint_config/joint_position_limit/lower/panda_joint3: -2.8973
  • /robot_config/joint_config/joint_position_limit/lower/panda_joint4: -3.0718
  • /robot_config/joint_config/joint_position_limit/lower/panda_joint5: -2.8973
  • /robot_config/joint_config/joint_position_limit/lower/panda_joint6: -0.0175
  • /robot_config/joint_config/joint_position_limit/lower/panda_joint7: -2.8973
  • /robot_config/joint_config/joint_position_limit/upper/panda_joint1: 2.8973
  • /robot_config/joint_config/joint_position_limit/upper/panda_joint2: 1.7628
  • /robot_config/joint_config/joint_position_limit/upper/panda_joint3: 2.8973
  • /robot_config/joint_config/joint_position_limit/upper/panda_joint4: -0.0698
  • /robot_config/joint_config/joint_position_limit/upper/panda_joint5: 2.8973
  • /robot_config/joint_config/joint_position_limit/upper/panda_joint6: 3.7525
  • /robot_config/joint_config/joint_position_limit/upper/panda_joint7: 2.8973
  • /robot_config/joint_config/joint_velocity_limit/panda_joint1: 2.175
  • /robot_config/joint_config/joint_velocity_limit/panda_joint2: 2.175
  • /robot_config/joint_config/joint_velocity_limit/panda_joint3: 2.175
  • /robot_config/joint_config/joint_velocity_limit/panda_joint4: 2.175
  • /robot_config/joint_config/joint_velocity_limit/panda_joint5: 2.61
  • /robot_config/joint_config/joint_velocity_limit/panda_joint6: 2.61
  • /robot_config/joint_config/joint_velocity_limit/panda_joint7: 2.61
  • /robot_config/joint_names: ['panda_joint1', ...
  • /robot_config/neutral_pose/panda_joint1: -0.0177920602278
  • /robot_config/neutral_pose/panda_joint2: -0.760123541104
  • /robot_config/neutral_pose/panda_joint3: 0.0197826070234
  • /robot_config/neutral_pose/panda_joint4: -2.34205014054
  • /robot_config/neutral_pose/panda_joint5: 0.0298405313558
  • /robot_config/neutral_pose/panda_joint6: 1.54119352986
  • /robot_config/neutral_pose/panda_joint7: 0.753448658975
  • /robot_description: <?xml version="1....
  • /robot_description_kinematics/panda_arm/kinematics_solver: kdl_kinematics_pl...
  • /robot_description_kinematics/panda_arm/kinematics_solver_search_resolution: 0.005
  • /robot_description_kinematics/panda_arm/kinematics_solver_timeout: 0.05
  • /robot_description_planning/joint_limits/panda_finger_joint1/has_acceleration_limits: False
  • /robot_description_planning/joint_limits/panda_finger_joint1/has_velocity_limits: True
  • /robot_description_planning/joint_limits/panda_finger_joint1/max_acceleration: 0
  • /robot_description_planning/joint_limits/panda_finger_joint1/max_velocity: 0.1
  • /robot_description_planning/joint_limits/panda_finger_joint2/has_acceleration_limits: False
  • /robot_description_planning/joint_limits/panda_finger_joint2/has_velocity_limits: True
  • /robot_description_planning/joint_limits/panda_finger_joint2/max_acceleration: 0
  • /robot_description_planning/joint_limits/panda_finger_joint2/max_velocity: 0.1
  • /robot_description_planning/joint_limits/panda_joint1/has_acceleration_limits: True
  • /robot_description_planning/joint_limits/panda_joint1/has_velocity_limits: True
  • /robot_description_planning/joint_limits/panda_joint1/max_acceleration: 3.75
  • /robot_description_planning/joint_limits/panda_joint1/max_velocity: 2.175
  • /robot_description_planning/joint_limits/panda_joint2/has_acceleration_limits: True
  • /robot_description_planning/joint_limits/panda_joint2/has_velocity_limits: True
  • /robot_description_planning/joint_limits/panda_joint2/max_acceleration: 1.875
  • /robot_description_planning/joint_limits/panda_joint2/max_velocity: 2.175
  • /robot_description_planning/joint_limits/panda_joint3/has_acceleration_limits: True
  • /robot_description_planning/joint_limits/panda_joint3/has_velocity_limits: True
  • /robot_description_planning/joint_limits/panda_joint3/max_acceleration: 2.5
  • /robot_description_planning/joint_limits/panda_joint3/max_velocity: 2.175
  • /robot_description_planning/joint_limits/panda_joint4/has_acceleration_limits: True
  • /robot_description_planning/joint_limits/panda_joint4/has_velocity_limits: True
  • /robot_description_planning/joint_limits/panda_joint4/max_acceleration: 3.125
  • /robot_description_planning/joint_limits/panda_joint4/max_velocity: 2.175
  • /robot_description_planning/joint_limits/panda_joint5/has_acceleration_limits: True
  • /robot_description_planning/joint_limits/panda_joint5/has_velocity_limits: True
  • /robot_description_planning/joint_limits/panda_joint5/max_acceleration: 3.75
  • /robot_description_planning/joint_limits/panda_joint5/max_velocity: 2.61
  • /robot_description_planning/joint_limits/panda_joint6/has_acceleration_limits: True
  • /robot_description_planning/joint_limits/panda_joint6/has_velocity_limits: True
  • /robot_description_planning/joint_limits/panda_joint6/max_acceleration: 5
  • /robot_description_planning/joint_limits/panda_joint6/max_velocity: 2.61
  • /robot_description_planning/joint_limits/panda_joint7/has_acceleration_limits: True
  • /robot_description_planning/joint_limits/panda_joint7/has_velocity_limits: True
  • /robot_description_planning/joint_limits/panda_joint7/max_acceleration: 5
  • /robot_description_planning/joint_limits/panda_joint7/max_velocity: 2.61
  • /robot_description_semantic: <?xml version="1....
  • /rosdistro: melodic
  • /rosversion: 1.14.9
  • /use_sim_time: True

NODES
/
base_to_link0 (tf/static_transform_publisher)
controller_spawner (controller_manager/controller_manager)
controller_spawner_stopped (controller_manager/controller_manager)
gazebo (gazebo_ros/gzserver)
gazebo_gui (gazebo_ros/gzclient)
gripper_action_server_emulator (panda_sim_custom_action_server/start_gripper_action_server.py)
joint_trajectory_server_emulator (panda_sim_custom_action_server/start_joint_trajectory_server.py)
move_group (moveit_ros_move_group/move_group)
panda_gripper_controller_spawner_stopped (controller_manager/controller_manager)
robot_description (gazebo_ros/spawn_model)
robot_state_publisher (robot_state_publisher/robot_state_publisher)
topic_remap (topic_tools/relay)
world_to_base (tf/static_transform_publisher)

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

setting /run_id to 5e628c3c-10bf-11eb-ab11-ccd9ac1b6b7e
process[rosout-1]: started with pid [15273]
started core service [/rosout]
process[gazebo-2]: started with pid [15280]
process[gazebo_gui-3]: started with pid [15284]
process[robot_description-4]: started with pid [15292]
gzserver: symbol lookup error: /home/erdi/.local/lib/libgazebo_common.so.9: undefined symbol: _ZN8ignition10fuel_tools12ClientConfig12SetUserAgentERKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEE
process[base_to_link0-5]: started with pid [15327]
gzclient: symbol lookup error: /home/erdi/.local/lib/libgazebo_common.so.9: undefined symbol: _ZN8ignition10fuel_tools12ClientConfig12SetUserAgentERKNSt7__cxx1112basic_stringIcSt11char_traitsIcESaIcEEE
No handlers could be found for logger "roslaunch"
[gazebo-2] process has died [pid 15280, exit code 127, cmd /opt/ros/melodic/lib/gazebo_ros/gzserver -e ode /home/erdi/panda_sim_ws/src/panda_simulator/panda_gazebo/worlds/panda.world __name:=gazebo __log:=/home/erdi/.ros/log/5e628c3c-10bf-11eb-ab11-ccd9ac1b6b7e/gazebo-2.log].
log file: /home/erdi/.ros/log/5e628c3c-10bf-11eb-ab11-ccd9ac1b6b7e/gazebo-2*.log
[gazebo_gui-3] process has died [pid 15284, exit code 127, cmd /opt/ros/melodic/lib/gazebo_ros/gzclient __name:=gazebo_gui __log:=/home/erdi/.ros/log/5e628c3c-10bf-11eb-ab11-ccd9ac1b6b7e/gazebo_gui-3.log].
log file: /home/erdi/.ros/log/5e628c3c-10bf-11eb-ab11-ccd9ac1b6b7e/gazebo_gui-3*.log
process[world_to_base-6]: started with pid [15352]
process[controller_spawner-7]: started with pid [15361]
process[controller_spawner_stopped-8]: started with pid [15367]
process[panda_gripper_controller_spawner_stopped-9]: started with pid [15368]
process[robot_state_publisher-10]: started with pid [15371]
process[topic_remap-11]: started with pid [15387]
process[joint_trajectory_server_emulator-12]: started with pid [15406]
process[gripper_action_server_emulator-13]: started with pid [15418]
process[move_group-14]: started with pid [15426]
[ INFO] [1602969969.588789510]: Loading robot model 'panda'...
[ WARN] [1602969969.589429680]: Skipping virtual joint 'virtual_joint' because its child frame 'panda_link0' does not match the URDF frame 'world'
[ INFO] [1602969969.589452379]: No root/virtual joint specified in SRDF. Assuming fixed joint
[ INFO] [1602969969.656638256]: Publishing maintained planning scene on 'monitored_planning_scene'
[ INFO] [1602969969.658575677]: MoveGroup debug mode is ON
Starting planning scene monitors...
[ INFO] [1602969969.658602675]: Starting planning scene monitor
[ INFO] [1602969969.660220026]: Listening to '/planning_scene'
[ INFO] [1602969969.660242391]: Starting world geometry update monitor for collision objects, attached objects, octomap updates.
[ INFO] [1602969969.661754595]: Listening to '/collision_object'
[ INFO] [1602969969.663573199]: Listening to '/planning_scene_world' for planning scene world geometry
[ INFO] [1602969969.682061764]: Listening to '/camera/depth_registered/points' using message filter with target frame 'world '
[ INFO] [1602969969.685423060]: Listening to '/attached_collision_object' for attached collision objects
Planning scene monitors started.
[ INFO] [1602969969.710825032]: Initializing OMPL interface using ROS parameters
[ INFO] [1602969969.737104841]: Using planning interface 'OMPL'
[ INFO] [1602969969.739154280]: Param 'default_workspace_bounds' was not set. Using default value: 10
[ INFO] [1602969969.739521795]: Param 'start_state_max_bounds_error' was set to 0.1
[ INFO] [1602969969.739754431]: Param 'start_state_max_dt' was not set. Using default value: 0.5
[ INFO] [1602969969.739969345]: Param 'start_state_max_dt' was not set. Using default value: 0.5
[ INFO] [1602969969.740215014]: Param 'jiggle_fraction' was set to 0.05
[ INFO] [1602969969.740451233]: Param 'max_sampling_attempts' was not set. Using default value: 100
[ERROR] [1602969969.740529662]: Exception while loading planning adapter plugin 'default_planner_request_adapters/ResolveConstraintFrames': According to the loaded plugin descriptions the class default_planner_request_adapters/ResolveConstraintFrames with base class type planning_request_adapter::PlanningRequestAdapter does not exist. Declared types are default_planner_request_adapters/AddIterativeSplineParameterization default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/AddTimeParameterization default_planner_request_adapters/Empty default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints default_planner_request_adapters/FixWorkspaceBounds
[ INFO] [1602969969.740562703]: Using planning request adapter 'Fix Workspace Bounds'
[ INFO] [1602969969.740572853]: Using planning request adapter 'Fix Start State Bounds'
[ INFO] [1602969969.740585197]: Using planning request adapter 'Fix Start State In Collision'
[ INFO] [1602969969.740594080]: Using planning request adapter 'Fix Start State Path Constraints'
[ INFO] [1602969969.740606647]: Using planning request adapter 'Add Time Parameterization'
/usr/local/lib/python2.7/dist-packages/quaternion/numba_wrapper.py:21: UserWarning:

!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
Could not import from numba, which means that some
parts of this code may run MUCH more slowly. You
may wish to install numba.
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

warnings.warn(warning_text)
/usr/local/lib/python2.7/dist-packages/quaternion/calculus.py:475: UserWarning:

!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
Could not import from scipy, which means that derivatives
and integrals will use less accurate finite-differencing
techniques. You may want to install scipy.
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

warnings.warn(warning_text)
/usr/local/lib/python2.7/dist-packages/quaternion/numba_wrapper.py:21: UserWarning:

!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
Could not import from numba, which means that some
parts of this code may run MUCH more slowly. You
may wish to install numba.
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

warnings.warn(warning_text)
/usr/local/lib/python2.7/dist-packages/quaternion/calculus.py:475: UserWarning:

!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
Could not import from scipy, which means that derivatives
and integrals will use less accurate finite-differencing
techniques. You may want to install scipy.
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

warnings.warn(warning_text)

catkin build error

Hello! I suffered this error when I catkin build. Could you help me with this? Thanks!

Errors << franka_interface:make /home/airlab/catkin_ws/logs/franka_interface/build.make.002.log
/home/airlab/catkin_ws/src/franka_ros_interface/franka_interface/src/robot_state_controller.cpp: In member function ‘void franka_interface::CustomFrankaStateController::publishFrankaState(const ros::Time&)’:
/home/airlab/catkin_ws/src/franka_ros_interface/franka_interface/src/robot_state_controller.cpp:361:39: error: ‘struct franka::RobotState’ has no member named ‘NE_T_EE’; did you mean ‘O_T_EE’?
static_assert(sizeof(robot_state_.NE_T_EE) == sizeof(robot_state_.O_T_EE),
^~~~~~~
O_T_EE
/home/airlab/catkin_ws/src/franka_ros_interface/franka_interface/src/robot_state_controller.cpp:369:63: error: ‘struct franka::RobotState’ has no member named ‘F_T_NE’; did you mean ‘F_T_EE’?
publisher_franka_state_.msg_.F_T_NE[i] = robot_state_.F_T_NE[i];
^~~~~~
F_T_EE
/home/airlab/catkin_ws/src/franka_ros_interface/franka_interface/src/robot_state_controller.cpp:370:64: error: ‘struct franka::RobotState’ has no member named ‘NE_T_EE’; did you mean ‘O_T_EE’?
publisher_franka_state_.msg_.NE_T_EE[i] = robot_state_.NE_T_EE[i];
^~~~~~~
O_T_EE
/home/airlab/catkin_ws/src/franka_ros_interface/franka_interface/src/robot_state_controller.cpp: In member function ‘void franka_interface::CustomFrankaStateController::publishTransforms(const ros::Time&)’:
/home/airlab/catkin_ws/src/franka_ros_interface/franka_interface/src/robot_state_controller.cpp:474:74: error: ‘struct franka::RobotState’ has no member named ‘F_T_NE’; did you mean ‘F_T_EE’?
tf::StampedTransform stamped_transform(convertArrayToTf(robot_state_.F_T_NE), time,
^~~~~~
F_T_EE
/home/airlab/catkin_ws/src/franka_ros_interface/franka_interface/src/robot_state_controller.cpp:480:76: error: ‘struct franka::RobotState’ has no member named ‘NE_T_EE’; did you mean ‘O_T_EE’?
stamped_transform = tf::StampedTransform(convertArrayToTf(robot_state_.NE_T_EE), time,
^~~~~~~
O_T_EE

Cartesian Pose Control as directly supported by Panda

Hi,

I know this is related to #17 and task-space cartesian pose control can be achieved via torque control and a PD controller.

However, the Panda HW interface also supports direct cartesian pose control.

This is implementable in a pretty straightforward manner in franka_ros_interface by subscribing for example to a TF topic like /franka_ros_interface/motion_controller/arm/cartesian_pose_commands.

However, it would also be interesting to have this functionality in the simulator, for example in a file here. Given that I don't have a Panda at the moment to find out how the real one behaves with the cartesian interface, I can not implement this simulation functionality right now.

Is it planned to also support this in simulator or would you always use the route of torque control (supported in simulation already) + PD controller. If so, this is the only example I found so far, is there also a C++ version already existing for it?

Error: Moveit - Gazebo communication

When building the project like your tutorial, I get an error when executing the planned path in moveit.

[ INFO] [1614583594.577708066, 101.569000000]: Execution request received [ERROR] [1614583594.577888662, 101.569000000]: Unable to identify any set of controllers that can actuate the specified joints: [ panda_joint1 panda_joint2 panda_joint3 panda_joint4 panda_joint5 panda_joint6 panda_joint7 ] [ERROR] [1614583594.577946947, 101.569000000]: Known controllers and their joints:

Do I have to make changes in Gazebo first? or probably choose the right controller in the Moveit configs?

Minjerk python 3

I'm trying to run the simulator in ros noetic on ubuntu.

I compiled correctly the simulator. I needed to hand compile even the franka-ros package because the package is not available in noetic.

The biggest problem in compiling is that rosdep is not working so you have to run the command rosdep instal --rosdistro noetic [...] and for each package that it is saying to be missing you have to add it with apt install [...].

After that I tried to run the simulator with roslaunch panda_gazebo panda_world.launch but the scripts joint_trajectory_action_server.py and gripper_action_server where looking for the command python that was not present on my system so i changed it with python3.

Even after adding python3 I had some problems with the dependencies, the one listed in requirements.txtare not sufficient.
Now python cannot find the package minjerk that is widely use inside the scripts. I can't find it on PyPI I think it is refering to this one. Is it that? if yes how do you advice to install it?

Gazebo not launched following Docker Build instructions

Hi,

I followed the docker instructions (noetic-devel) and everything seems to be successfully built. But when I ran roslaunch panda_gazebo panda_world.launch, I encountered an issue with gazebo:

[ INFO] [1633600245.792627116]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1633600245.793902469]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting...
X Error of failed request:  BadAlloc (insufficient resources for operation)
  Major opcode of failed request:  149 ()
  Minor opcode of failed request:  2
  Serial number of failed request:  35
  Current serial number in output stream:  36
the rosdep view is empty: call 'sudo rosdep init' and 'rosdep update'

Gazebo was not launched.

Any help would be very much appreciated.

Full output below:

~/panda_sim_ws$ roslaunch panda_gazebo panda_world.launch
WARNING: cannot create log directory [/home/chiaman/.ros/log/09f6fabe-2754-11ec-a7d9-fc34974b282e]. Please set ROS_LOG_DIR to a writable location.
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
/usr/bin/du: cannot access '/home/chiaman/.ros/log': No such file or directory

xacro: in-order processing became default in ROS Melodic. You can drop the option.
started roslaunch server http://localhost:42551/

SUMMARY
========

PARAMETERS
 * /SIMULATOR_: True
 * /arm/gravity_tip_name: panda_hand
 * /arm/root_name: panda_link0
 * /arm/tip_name: panda_hand
 * /controllers_config/default_controller: panda_simulator/p...
 * /controllers_config/position_controller: panda_simulator/p...
 * /controllers_config/torque_controller: panda_simulator/e...
 * /controllers_config/velocity_controller: panda_simulator/v...
 * /franka_gripper/robot_ip: sim
 * /gazebo/enable_ros_network: True
 * /gripper_config/default_grasp_epsilon/inner: 0.005
 * /gripper_config/default_grasp_epsilon/outer: 0.005
 * /gripper_config/default_speed: 0.1
 * /gripper_config/joint_names: ['panda_finger_jo...
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/effort_joint_gravity_controller/type: panda_sim_control...
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/effort_joint_torque_controller/topic: /panda_simulator/...
 * /panda_simulator/effort_joint_torque_controller/type: panda_sim_control...
 * /panda_simulator/joint_state_controller/publish_rate: 100
 * /panda_simulator/joint_state_controller/type: joint_state_contr...
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/joint: panda_finger_joint1
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/d: 0.5
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/i: 50
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/p: 5000
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/joint: panda_finger_joint2
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/d: 0.5
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/i: 50
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/p: 5000
 * /panda_simulator/panda_gripper_controller/pub_topic: /franka_gripper/j...
 * /panda_simulator/panda_gripper_controller/type: panda_sim_control...
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/d: 25.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/d: 30.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/d: 30.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/d: 50.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/d: 8.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/d: 5.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/i: 1.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/d: 4.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/topic_joint_command: /panda_simulator/...
 * /panda_simulator/position_joint_position_controller/topic_set_speed_ratio: /panda_simulator/...
 * /panda_simulator/position_joint_position_controller/type: panda_sim_control...
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/d: 0.1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/p: 10
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/d: 0.1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/i: 1.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/p: 100
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/p: 0.05
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/d: 0.1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/i: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/p: 0.5
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/p: 1.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/p: 0.05
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/p: 0.05
 * /panda_simulator/velocity_joint_velocity_controller/topic: /panda_simulator/...
 * /panda_simulator/velocity_joint_velocity_controller/type: panda_sim_control...
 * /robot_config/arm_id: panda
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint1: 15.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint2: 7.5
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint3: 10.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint4: 12.5
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint5: 15.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint6: 20.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint7: 20.0
 * /robot_config/joint_config/joint_effort_limit/panda_joint1: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint2: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint3: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint4: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint5: 12
 * /robot_config/joint_config/joint_effort_limit/panda_joint6: 12
 * /robot_config/joint_config/joint_effort_limit/panda_joint7: 12
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint1: -2.8973
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint2: -1.7628
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint3: -2.8973
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint4: -3.0718
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint5: -2.8973
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint6: -0.0175
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint7: -2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint1: 2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint2: 1.7628
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint3: 2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint4: -0.0698
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint5: 2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint6: 3.7525
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint7: 2.8973
 * /robot_config/joint_config/joint_velocity_limit/panda_joint1: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint2: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint3: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint4: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint5: 2.61
 * /robot_config/joint_config/joint_velocity_limit/panda_joint6: 2.61
 * /robot_config/joint_config/joint_velocity_limit/panda_joint7: 2.61
 * /robot_config/joint_names: ['panda_joint1', ...
 * /robot_config/neutral_pose/panda_joint1: -0.01779206022777...
 * /robot_config/neutral_pose/panda_joint2: -0.7601235411041661
 * /robot_config/neutral_pose/panda_joint3: 0.019782607023391807
 * /robot_config/neutral_pose/panda_joint4: -2.342050140544315
 * /robot_config/neutral_pose/panda_joint5: 0.029840531355804868
 * /robot_config/neutral_pose/panda_joint6: 1.5411935298621688
 * /robot_config/neutral_pose/panda_joint7: 0.7534486589746342
 * /robot_description: <?xml version="1....
 * /rosdistro: noetic
 * /rosversion: 1.15.13
 * /use_sim_time: True

NODES
  /
    base_to_link0 (tf/static_transform_publisher)
    controller_spawner (controller_manager/controller_manager)
    controller_spawner_stopped (controller_manager/controller_manager)
    gazebo (gazebo_ros/gzserver)
    gazebo_gui (gazebo_ros/gzclient)
    gripper_action_server_emulator (panda_sim_custom_action_server/start_gripper_action_server.py)
    joint_trajectory_server_emulator (panda_sim_custom_action_server/start_joint_trajectory_server.py)
    panda_gripper_controller_spawner_stopped (controller_manager/controller_manager)
    robot_description (gazebo_ros/spawn_model)
    robot_state_publisher (robot_state_publisher/robot_state_publisher)
    startup_script (panda_gazebo/force_neutral_pose.py)
    topic_remap (topic_tools/relay)
    world_to_base (tf/static_transform_publisher)

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

setting /run_id to 09f6fabe-2754-11ec-a7d9-fc34974b282e
process[rosout-1]: started with pid [14240]
started core service [/rosout]
process[gazebo-2]: started with pid [14247]
process[gazebo_gui-3]: started with pid [14251]
process[robot_description-4]: started with pid [14256]
process[base_to_link0-5]: started with pid [14258]
process[world_to_base-6]: started with pid [14259]
process[controller_spawner-7]: started with pid [14260]
process[controller_spawner_stopped-8]: started with pid [14262]
process[panda_gripper_controller_spawner_stopped-9]: started with pid [14267]
process[robot_state_publisher-10]: started with pid [14271]
process[topic_remap-11]: started with pid [14274]
process[joint_trajectory_server_emulator-12]: started with pid [14275]
process[gripper_action_server_emulator-13]: started with pid [14277]
process[startup_script-14]: started with pid [14285]
INFO: cannot create a symlink to latest log directory: [Errno 2] No such file or directory: '/home/chiaman/.ros/log/latest'
/usr/local/lib/python3.8/dist-packages/quaternion/numba_wrapper.py:21: UserWarning: 

!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
Could not import from numba, which means that some
parts of this code may run MUCH more slowly.  You
may wish to install numba.
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

  warnings.warn(warning_text)
/usr/local/lib/python3.8/dist-packages/quaternion/calculus.py:475: UserWarning: 

!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
Could not import from scipy, which means that derivatives
and integrals will use less accurate finite-differencing
techniques.  You may want to install scipy.
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

  warnings.warn(warning_text)
the rosdep view is empty: call 'sudo rosdep init' and 'rosdep update'
/usr/local/lib/python3.8/dist-packages/quaternion/numba_wrapper.py:21: UserWarning: 

!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
Could not import from numba, which means that some
parts of this code may run MUCH more slowly.  You
may wish to install numba.
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

  warnings.warn(warning_text)
/usr/local/lib/python3.8/dist-packages/quaternion/calculus.py:475: UserWarning: 

!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
Could not import from scipy, which means that derivatives
and integrals will use less accurate finite-differencing
techniques.  You may want to install scipy.
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

  warnings.warn(warning_text)
[ INFO] [1633600245.711973378]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1633600245.713547151]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
X Error of failed request:  BadAlloc (insufficient resources for operation)
  Major opcode of failed request:  149 ()
  Minor opcode of failed request:  2
  Serial number of failed request:  35
  Current serial number in output stream:  36
[ INFO] [1633600245.792627116]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1633600245.793902469]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting...
X Error of failed request:  BadAlloc (insufficient resources for operation)
  Major opcode of failed request:  149 ()
  Minor opcode of failed request:  2
  Serial number of failed request:  35
  Current serial number in output stream:  36
the rosdep view is empty: call 'sudo rosdep init' and 'rosdep update'

issue with the r.velocities()

Thanks for your work, it helps me a lot. now I meet a problem, I changed the office code "cartesian_impedance_example_controller.cpp" to python but found the arm abnormal jitter
in the gazebo,and then I print the r.velocities() and found no zero at start. Then I wrote a easy code
rospy.init_node("test_node")
r = PandaArm()
rate = rospy.Rate(400)
while not rospy.is_shutdown():
print r.velocities()
but got the output
[ 2.39455761e-02 1.89977710e-03 -2.23809963e-02 -3.04818945e-02
7.50835108e-02 3.56811108e-01 4.63242645e+00]
[ 2.39455761e-02 1.89977710e-03 -2.23809963e-02 -3.04818945e-02
7.50835108e-02 3.56811108e-01 4.63242645e+00]
[ 2.39455761e-02 1.89977710e-03 -2.23809963e-02 -3.04818945e-02
7.50835108e-02 3.56811108e-01 4.63242645e+00]
[ 0.06962769 0.00872245 -0.07593144 -0.03078833 0.05199004 0.36187647
4.62442711]
[ 0.06962769 0.00872245 -0.07593144 -0.03078833 0.05199004 0.36187647
4.62442711]
[ 0.06962769 0.00872245 -0.07593144 -0.03078833 0.05199004 0.36187647
4.62442711]
[ 0.06962769 0.00872245 -0.07593144 -0.03078833 0.05199004 0.36187647
4.62442711]
[ 0.06962769 0.00872245 -0.07593144 -0.03078833 0.05199004 0.36187647
4.62442711]

How can I fix this?thank you~

Fail to startup

Hi !
NIce work there but I can't startup the simulation. Or actually gazebo start but end up crashing before starting moveit...

... logging to /home/altair/.ros/log/c59f8780-753f-11eb-8ab4-3c6aa7b729ab/roslaunch-altair-88694.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

xacro: in-order processing became default in ROS Melodic. You can drop the option.
started roslaunch server http://altair:35151/

SUMMARY
========

PARAMETERS
 * /SIMULATOR_: True
 * /arm/gravity_tip_name: panda_hand
 * /arm/root_name: panda_link0
 * /arm/tip_name: panda_hand
 * /controllers_config/default_controller: panda_simulator/p...
 * /controllers_config/position_controller: panda_simulator/p...
 * /controllers_config/torque_controller: panda_simulator/e...
 * /controllers_config/velocity_controller: panda_simulator/v...
 * /franka_gripper/robot_ip: sim
 * /gazebo/enable_ros_network: True
 * /gripper_config/default_grasp_epsilon/inner: 0.005
 * /gripper_config/default_grasp_epsilon/outer: 0.005
 * /gripper_config/default_speed: 0.1
 * /gripper_config/joint_names: ['panda_finger_jo...
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/effort_joint_gravity_controller/type: panda_sim_control...
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/effort_joint_torque_controller/topic: /panda_simulator/...
 * /panda_simulator/effort_joint_torque_controller/type: panda_sim_control...
 * /panda_simulator/joint_state_controller/publish_rate: 100
 * /panda_simulator/joint_state_controller/type: joint_state_contr...
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/joint: panda_finger_joint1
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/d: 0.5
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/i: 50
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/p: 5000
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/joint: panda_finger_joint2
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/d: 0.5
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/i: 50
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/p: 5000
 * /panda_simulator/panda_gripper_controller/pub_topic: /franka_gripper/j...
 * /panda_simulator/panda_gripper_controller/type: panda_sim_control...
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/d: 25.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/d: 30.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/d: 30.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/d: 50.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/d: 8.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/d: 5.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/i: 1.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/d: 4.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/topic_joint_command: /panda_simulator/...
 * /panda_simulator/position_joint_position_controller/topic_set_speed_ratio: /panda_simulator/...
 * /panda_simulator/position_joint_position_controller/type: panda_sim_control...
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/d: 0.1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/p: 10
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/d: 0.1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/i: 1.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/p: 100
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/p: 0.05
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/d: 0.1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/i: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/p: 0.5
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/p: 1.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/p: 0.05
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/p: 0.05
 * /panda_simulator/velocity_joint_velocity_controller/topic: /panda_simulator/...
 * /panda_simulator/velocity_joint_velocity_controller/type: panda_sim_control...
 * /robot_config/arm_id: panda
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint1: 15.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint2: 7.5
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint3: 10.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint4: 12.5
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint5: 15.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint6: 20.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint7: 20.0
 * /robot_config/joint_config/joint_effort_limit/panda_joint1: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint2: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint3: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint4: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint5: 12
 * /robot_config/joint_config/joint_effort_limit/panda_joint6: 12
 * /robot_config/joint_config/joint_effort_limit/panda_joint7: 12
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint1: -2.8973
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint2: -1.7628
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint3: -2.8973
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint4: -3.0718
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint5: -2.8973
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint6: -0.0175
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint7: -2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint1: 2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint2: 1.7628
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint3: 2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint4: -0.0698
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint5: 2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint6: 3.7525
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint7: 2.8973
 * /robot_config/joint_config/joint_velocity_limit/panda_joint1: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint2: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint3: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint4: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint5: 2.61
 * /robot_config/joint_config/joint_velocity_limit/panda_joint6: 2.61
 * /robot_config/joint_config/joint_velocity_limit/panda_joint7: 2.61
 * /robot_config/joint_names: ['panda_joint1', ...
 * /robot_config/neutral_pose/panda_joint1: -0.0177920602278
 * /robot_config/neutral_pose/panda_joint2: -0.760123541104
 * /robot_config/neutral_pose/panda_joint3: 0.0197826070234
 * /robot_config/neutral_pose/panda_joint4: -2.34205014054
 * /robot_config/neutral_pose/panda_joint5: 0.0298405313558
 * /robot_config/neutral_pose/panda_joint6: 1.54119352986
 * /robot_config/neutral_pose/panda_joint7: 0.753448658975
 * /robot_description: <?xml version="1....
 * /rosdistro: melodic
 * /rosversion: 1.14.10
 * /use_sim_time: True

NODES
  /
    base_to_link0 (tf/static_transform_publisher)
    controller_spawner (controller_manager/controller_manager)
    controller_spawner_stopped (controller_manager/controller_manager)
    gazebo (gazebo_ros/gzserver)
    gazebo_gui (gazebo_ros/gzclient)
    gripper_action_server_emulator (panda_sim_custom_action_server/start_gripper_action_server.py)
    joint_trajectory_server_emulator (panda_sim_custom_action_server/start_joint_trajectory_server.py)
    panda_gripper_controller_spawner_stopped (controller_manager/controller_manager)
    robot_description (gazebo_ros/spawn_model)
    robot_state_publisher (robot_state_publisher/robot_state_publisher)
    startup_script (panda_gazebo/force_neutral_pose.py)
    topic_remap (topic_tools/relay)
    world_to_base (tf/static_transform_publisher)

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

setting /run_id to c59f8780-753f-11eb-8ab4-3c6aa7b729ab
process[rosout-1]: started with pid [88718]
started core service [/rosout]
process[gazebo-2]: started with pid [88725]
process[gazebo_gui-3]: started with pid [88730]
process[robot_description-4]: started with pid [88735]
process[base_to_link0-5]: started with pid [88736]
process[world_to_base-6]: started with pid [88737]
process[controller_spawner-7]: started with pid [88742]
process[controller_spawner_stopped-8]: started with pid [88748]
process[panda_gripper_controller_spawner_stopped-9]: started with pid [88750]
process[robot_state_publisher-10]: started with pid [88751]
process[topic_remap-11]: started with pid [88753]
process[joint_trajectory_server_emulator-12]: started with pid [88761]
process[gripper_action_server_emulator-13]: started with pid [88768]
process[startup_script-14]: started with pid [88770]
[ INFO] [1614020233.765319897]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1614020233.770067651]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1614020233.803572784]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1614020233.805753050]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting...
/home/altair/.themes/WhiteSur-light/gtk-2.0/menubar-toolbar.rc:166: error: invalid string constant "misc_button_label", expected valid string constant
[ INFO] [1614020235.133350323]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1614020235.406484999, 0.151000000]: Physics dynamic reconfigure ready.
[ INFO] [1614020235.419390794, 0.151000000]: Loading gazebo_ros_control plugin
[ INFO] [1614020235.421845752, 0.151000000]: Starting gazebo_ros_control plugin in namespace: 
[ INFO] [1614020235.422297885, 0.151000000]: gazebo_ros_control plugin is waiting for model URDF in parameter [/robot_description] on the ROS param server.
[ INFO] [1614020235.546770962, 0.151000000]: Loaded gazebo_ros_control.
[ INFO] [1614020235.555778658, 0.151000000]: Unable to find Acceleration values for joint panda_finger_joint1...
[ INFO] [1614020235.555896437, 0.151000000]: Unable to find Acceleration values for joint panda_finger_joint2...
[ INFO] [1614020235.631213566, 0.215000000]: Initializing JointArrayController(type:/panda_simulator/position_joint_position_controller) with 7 joints.
[ INFO] [1614020235.631421744, 0.216000000]: Loading sub-controller 'panda_joint1_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller
[ INFO] [1614020235.654869085, 0.239000000]: Loading sub-controller 'panda_joint2_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller
[ INFO] [1614020235.669799615, 0.254000000]: Loading sub-controller 'panda_joint3_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller
[ INFO] [1614020235.681945903, 0.266000000]: Loading sub-controller 'panda_joint4_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller
[ INFO] [1614020235.696809529, 0.280000000]: Loading sub-controller 'panda_joint5_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller
[ INFO] [1614020235.708732240, 0.292000000]: Loading sub-controller 'panda_joint6_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller
[ INFO] [1614020235.720477100, 0.304000000]: Loading sub-controller 'panda_joint7_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller
Loaded 'panda_simulator/position_joint_position_controller'
[ INFO] [1614020235.745322537, 0.329000000]: Initializing JointArrayController(type:/panda_simulator/velocity_joint_velocity_controller) with 7 joints.
[ INFO] [1614020235.745385625, 0.329000000]: Loading sub-controller 'panda_joint1_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller
[ INFO] [1614020235.761408622, 0.345000000]: Loading sub-controller 'panda_joint2_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller
[ INFO] [1614020235.776235970, 0.359000000]: Loading sub-controller 'panda_joint3_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller
[ INFO] [1614020235.791895149, 0.375000000]: Loading sub-controller 'panda_joint4_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller
[ INFO] [1614020235.815337450, 0.398000000]: Loading sub-controller 'panda_joint5_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller
[ INFO] [1614020235.860027821, 0.443000000]: Loading sub-controller 'panda_joint6_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller
[ INFO] [1614020235.885755123, 0.469000000]: Loading sub-controller 'panda_joint7_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller
Loaded 'panda_simulator/velocity_joint_velocity_controller'
[ INFO] [1614020235.908492069, 0.491000000]: Initializing PandaGripperController with 2 joints.
[ INFO] [1614020235.908968077, 0.492000000]: Loading sub-controller 'panda_finger_joint1_controller', Namespace: /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller
[ INFO] [1614020235.927127257, 0.510000000]: Loading sub-controller 'panda_finger_joint2_controller', Namespace: /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller
Loaded 'panda_simulator/panda_gripper_controller'
Loaded 'panda_simulator/joint_state_controller'
[ INFO] [1614020235.982535824, 0.565000000]: Initializing JointArrayController(type:/panda_simulator/effort_joint_gravity_controller) with 7 joints.
[ INFO] [1614020235.982615372, 0.565000000]: Loading sub-controller 'panda_joint1_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint1_controller
[ INFO] [1614020235.984036071, 0.567000000]: Loading sub-controller 'panda_joint2_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint2_controller
[ INFO] [1614020235.984482764, 0.567000000]: Loading sub-controller 'panda_joint3_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint3_controller
[ INFO] [1614020235.984830693, 0.568000000]: Loading sub-controller 'panda_joint4_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint4_controller
[ INFO] [1614020235.985170006, 0.568000000]: Loading sub-controller 'panda_joint5_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint5_controller
[ INFO] [1614020235.985488650, 0.568000000]: Loading sub-controller 'panda_joint6_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint6_controller
[ INFO] [1614020235.985816361, 0.569000000]: Loading sub-controller 'panda_joint7_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint7_controller
Loaded 'panda_simulator/effort_joint_gravity_controller'
Started ['panda_simulator/panda_gripper_controller'] successfully
Started ['panda_simulator/position_joint_position_controller'] successfully
[ INFO] [1614020235.995781021, 0.579000000]: Initializing JointArrayController(type:/panda_simulator/effort_joint_torque_controller) with 7 joints.
[ INFO] [1614020235.995857193, 0.579000000]: Loading sub-controller 'panda_joint1_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint1_controller
[ INFO] [1614020236.000283847, 0.583000000]: Loading sub-controller 'panda_joint2_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint2_controller
[ INFO] [1614020236.002639880, 0.585000000]: Loading sub-controller 'panda_joint3_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint3_controller
[ INFO] [1614020236.005046177, 0.588000000]: Loading sub-controller 'panda_joint4_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint4_controller
[ INFO] [1614020236.006751958, 0.590000000]: Loading sub-controller 'panda_joint5_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint5_controller
[ INFO] [1614020236.008132262, 0.591000000]: Loading sub-controller 'panda_joint6_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint6_controller
[ INFO] [1614020236.009505021, 0.592000000]: Loading sub-controller 'panda_joint7_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint7_controller
Loaded 'panda_simulator/effort_joint_torque_controller'
Started ['panda_simulator/joint_state_controller'] successfully
[controller_spawner-7] process has finished cleanly
log file: /home/altair/.ros/log/c59f8780-753f-11eb-8ab4-3c6aa7b729ab/controller_spawner-7*.log
[controller_spawner_stopped-8] process has finished cleanly
log file: /home/altair/.ros/log/c59f8780-753f-11eb-8ab4-3c6aa7b729ab/controller_spawner_stopped-8*.log
[panda_gripper_controller_spawner_stopped-9] process has finished cleanly
log file: /home/altair/.ros/log/c59f8780-753f-11eb-8ab4-3c6aa7b729ab/panda_gripper_controller_spawner_stopped-9*.log
Segmentation fault (core dumped)
[ERROR] [1614020256.122124, 0.612000]: SetModelConfiguration service failed. Exiting.
[gazebo-2] process has died [pid 88725, exit code 139, cmd /opt/ros/melodic/lib/gazebo_ros/gzserver -e ode /home/altair/catkin_panda/src/panda_simulator/panda_gazebo/worlds/panda.world __name:=gazebo __log:=/home/altair/.ros/log/c59f8780-753f-11eb-8ab4-3c6aa7b729ab/gazebo-2.log].
log file: /home/altair/.ros/log/c59f8780-753f-11eb-8ab4-3c6aa7b729ab/gazebo-2*.log
[robot_description-4] process has died [pid 88735, exit code 1, cmd /opt/ros/melodic/lib/gazebo_ros/spawn_model -param robot_description -urdf -model panda -J panda::panda_joint1 0.000 -J panda::panda_joint2 -0.785 -J panda::panda_joint3 0.0 -J panda::panda_joint4 -2.356 -J panda::panda_joint5 0.0 -J panda::panda_joint6 1.57 -J panda::panda_joint7 0.785 __name:=robot_description __log:=/home/altair/.ros/log/c59f8780-753f-11eb-8ab4-3c6aa7b729ab/robot_description-4.log].
log file: /home/altair/.ros/log/c59f8780-753f-11eb-8ab4-3c6aa7b729ab/robot_description-4*.log

Moveit Execution

Hi @justagist!
I have a second question: The simulator should support MoveIt, right? I can plan trajectories like normal, but I cannot execute them on the simulator.

Moveit wants to subscribe to a position_joint_trajectory_controller/follow_joint_trajectory but this fails, because the sim_controllers are used. But they do not support FollowJointTrajectory input. Is there a way to execute the trajectories on the simulator with one controller?

I'm not sure if I just didn't find this option or if it is necessary to write a new FollowJointTrajectory controller using one of the sim-controllers.

RvizMarkers

Hi!
Your simulation frameworks looks really promising and i want to try it! But I have one simple problem: What is the RvizMarker used in the examples? It is required to run the example but i cannot find it anywhere.

Can you tell me which package I have to install?

How do I add an .stl to the gazebo simulation?

Thanks for such a great tool!

I'm trying to add a static object to my simulation (specifically an .stl file, named "shelves.stl"), but I'm having difficulties getting it to appear when I run roslaunch panda_gazebo panda_world.launch.

I've edited the panda.world file to include the stl file:

<?xml version="1.0" ?>
<sdf version="1.6">
  <world name="default">
    <include>
      <uri>model://ground_plane</uri>
    </include>

    <include>
      <uri>model://sun</uri>
    </include>

    <model name="shelves">
      <pose>0 0 0  0 0 0</pose>
      <static>true</static>
      <link name="body">
        <visual name="visual">
          <geometry>
            <mesh><uri>file://shelves.stl</uri></mesh>
          </geometry>
        </visual>
      </link>
    </model>

    <physics type="ode">
      <real_time_update_rate>1000.0</real_time_update_rate>
    </physics>
    
    <gravity>
      0.0 0.0 0.0
    </gravity>

    <gui fullscreen='0'>
    </gui>

  </world>
</sdf>

But it's not showing up. I am 99% certain it is an issue with where the .stl file is saved. I'm not quite certain where exactly panda_gazebo looks for meshes / stls, and the directories I've tried haven't worked. For what it's worth, I can get the .stl file to appear when I run gazebo panda.world from the directory containing shelves.stl, but of course this doesn't simulate the robot. Do you have a simple example showing where I need to store the .stl file?

Errors when starting example scripts

Hi,

roslaunch panda_gazebo panda_world.launch gives me following error:

(my_env) usr@usr-Precision-7740:~$ roslaunch panda_gazebo panda_world.launch 
... logging to /home/usr/.ros/log/0f5c8262-5b7f-11ec-860b-04ed335411c2/roslaunch-usr-Precision-7740-24186.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

xacro: in-order processing became default in ROS Melodic. You can drop the option.
started roslaunch server http://192.168.2.101:34367/

SUMMARY
========

PARAMETERS
 * /SIMULATOR_: True
 * /arm/gravity_tip_name: panda_hand
 * /arm/root_name: panda_link0
 * /arm/tip_name: panda_hand
 * /controllers_config/default_controller: panda_simulator/p...
 * /controllers_config/position_controller: panda_simulator/p...
 * /controllers_config/torque_controller: panda_simulator/e...
 * /controllers_config/velocity_controller: panda_simulator/v...
 * /franka_gripper/robot_ip: sim
 * /gazebo/enable_ros_network: True
 * /gripper_config/default_grasp_epsilon/inner: 0.005
 * /gripper_config/default_grasp_epsilon/outer: 0.005
 * /gripper_config/default_speed: 0.1
 * /gripper_config/joint_names: ['panda_finger_jo...
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/effort_joint_gravity_controller/type: panda_sim_control...
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/effort_joint_torque_controller/topic: /panda_simulator/...
 * /panda_simulator/effort_joint_torque_controller/type: panda_sim_control...
 * /panda_simulator/joint_state_controller/publish_rate: 100
 * /panda_simulator/joint_state_controller/type: joint_state_contr...
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/joint: panda_finger_joint1
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/d: 0.5
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/i: 50
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/p: 5000
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/joint: panda_finger_joint2
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/d: 0.5
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/i: 50
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/p: 5000
 * /panda_simulator/panda_gripper_controller/pub_topic: /franka_gripper/j...
 * /panda_simulator/panda_gripper_controller/type: panda_sim_control...
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/d: 25.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/d: 30.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/d: 30.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/d: 50.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/d: 8.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/d: 5.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/i: 1.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/d: 4.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/topic_joint_command: /panda_simulator/...
 * /panda_simulator/position_joint_position_controller/topic_set_speed_ratio: /panda_simulator/...
 * /panda_simulator/position_joint_position_controller/type: panda_sim_control...
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/d: 0.1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/p: 10
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/d: 0.1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/i: 1.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/p: 100
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/p: 0.05
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/d: 0.1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/i: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/p: 0.5
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/p: 1.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/p: 0.05
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/p: 0.05
 * /panda_simulator/velocity_joint_velocity_controller/topic: /panda_simulator/...
 * /panda_simulator/velocity_joint_velocity_controller/type: panda_sim_control...
 * /robot_config/arm_id: panda
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint1: 15.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint2: 7.5
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint3: 10.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint4: 12.5
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint5: 15.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint6: 20.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint7: 20.0
 * /robot_config/joint_config/joint_effort_limit/panda_joint1: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint2: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint3: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint4: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint5: 12
 * /robot_config/joint_config/joint_effort_limit/panda_joint6: 12
 * /robot_config/joint_config/joint_effort_limit/panda_joint7: 12
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint1: -2.8973
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint2: -1.7628
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint3: -2.8973
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint4: -3.0718
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint5: -2.8973
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint6: -0.0175
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint7: -2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint1: 2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint2: 1.7628
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint3: 2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint4: -0.0698
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint5: 2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint6: 3.7525
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint7: 2.8973
 * /robot_config/joint_config/joint_velocity_limit/panda_joint1: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint2: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint3: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint4: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint5: 2.61
 * /robot_config/joint_config/joint_velocity_limit/panda_joint6: 2.61
 * /robot_config/joint_config/joint_velocity_limit/panda_joint7: 2.61
 * /robot_config/joint_names: ['panda_joint1', ...
 * /robot_config/neutral_pose/panda_joint1: -0.0177920602278
 * /robot_config/neutral_pose/panda_joint2: -0.760123541104
 * /robot_config/neutral_pose/panda_joint3: 0.0197826070234
 * /robot_config/neutral_pose/panda_joint4: -2.34205014054
 * /robot_config/neutral_pose/panda_joint5: 0.0298405313558
 * /robot_config/neutral_pose/panda_joint6: 1.54119352986
 * /robot_config/neutral_pose/panda_joint7: 0.753448658975
 * /robot_description: <?xml version="1....
 * /rosdistro: melodic
 * /rosversion: 1.14.12
 * /use_sim_time: True

NODES
  /
    base_to_link0 (tf/static_transform_publisher)
    controller_spawner (controller_manager/controller_manager)
    controller_spawner_stopped (controller_manager/controller_manager)
    gazebo (gazebo_ros/gzserver)
    gazebo_gui (gazebo_ros/gzclient)
    gripper_action_server_emulator (panda_sim_custom_action_server/start_gripper_action_server.py)
    joint_trajectory_server_emulator (panda_sim_custom_action_server/start_joint_trajectory_server.py)
    panda_gripper_controller_spawner_stopped (controller_manager/controller_manager)
    robot_description (gazebo_ros/spawn_model)
    robot_state_publisher (robot_state_publisher/robot_state_publisher)
    startup_script (panda_gazebo/force_neutral_pose.py)
    topic_remap (topic_tools/relay)
    world_to_base (tf/static_transform_publisher)

ROS_MASTER_URI=http://localhost:11311

process[gazebo-1]: started with pid [24226]
process[gazebo_gui-2]: started with pid [24231]
process[robot_description-3]: started with pid [24236]
process[base_to_link0-4]: started with pid [24237]
process[world_to_base-5]: started with pid [24238]
process[controller_spawner-6]: started with pid [24243]
process[controller_spawner_stopped-7]: started with pid [24249]
process[panda_gripper_controller_spawner_stopped-8]: started with pid [24251]
process[robot_state_publisher-9]: started with pid [24252]
process[topic_remap-10]: started with pid [24253]
process[joint_trajectory_server_emulator-11]: started with pid [24255]
process[gripper_action_server_emulator-12]: started with pid [24266]
process[startup_script-13]: started with pid [24271]
[ INFO] [1639336652.639072509]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1639336652.640634079]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1639336652.727772024]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1639336652.728850759]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting...
[ INFO] [1639336653.927362864, 0.006000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1639336653.968940305, 0.046000000]: Physics dynamic reconfigure ready.
[ INFO] [1639336654.238104418, 0.173000000]: ft_sensor plugin reporting wrench values to the frame [panda_link7]
[ INFO] [1639336654.238133807, 0.173000000]: imu plugin missing <gaussianNoise>, defaults to 0.0
[robot_description-3] process has finished cleanly
log file: /home/usr/.ros/log/0f5c8262-5b7f-11ec-860b-04ed335411c2/robot_description-3*.log
[startup_script-13] process has finished cleanly
log file: /home/usr/.ros/log/0f5c8262-5b7f-11ec-860b-04ed335411c2/startup_script-13*.log
Traceback (most recent call last):
  File "/home/usr/panda_ws_moveit/src/panda_simulator/panda_sim_custom_action_server/scripts/start_joint_trajectory_server.py", line 83, in <module>
    main()
  File "/home/usr/panda_ws_moveit/src/panda_simulator/panda_sim_custom_action_server/scripts/start_joint_trajectory_server.py", line 79, in main
    start_server(args.rate)
  File "/home/usr/panda_ws_moveit/src/panda_simulator/panda_sim_custom_action_server/scripts/start_joint_trajectory_server.py", line 56, in start_server
    jtas.append(JointTrajectoryActionServer(dyn_cfg_srv, rate))
  File "/home/usr/panda_ws_moveit/src/panda_simulator/panda_sim_custom_action_server/src/panda_sim_custom_action_server/joint_trajectory_action_server.py", line 170, in __init__
    self._arm = franka_interface.ArmInterface(synchronous_pub=True)
  File "/home/usr/panda_ws_moveit/src/franka_ros_interface/franka_interface/src/franka_interface/arm.py", line 214, in __init__
    timeout_msg=err_msg, timeout=5.0)
  File "/home/usr/panda_ws_moveit/src/franka_ros_interface/franka_interface/src/franka_dataflow/wait_for.py", line 56, in wait_for
    raise OSError(errno.ETIMEDOUT, timeout_msg)
OSError: [Errno 110] Panda arm init failed to get current joint_states from /panda_simulator/custom_franka_state_controller/joint_states

And running roslaunch panda_sim_moveit sim_move_group.launch in a separate terminal gives following error:

(my_env) usr@usr-Precision-7740:~/panda_ws_moveit/src/panda_simulator$ roslaunch panda_sim_moveit sim_move_group.launch
... logging to /home/usr/.ros/log/0f5c8262-5b7f-11ec-860b-04ed335411c2/roslaunch-usr-Precision-7740-24662.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.

started roslaunch server http://192.168.2.101:39247/

SUMMARY
========

PARAMETERS
 * /move_group/allow_trajectory_execution: True
 * /move_group/controller_list: [{'default': True...
 * /move_group/hand/planner_configs: ['SBLkConfigDefau...
 * /move_group/jiggle_fraction: 0.05
 * /move_group/max_range: 5.0
 * /move_group/max_safe_path_cost: 1
 * /move_group/moveit_controller_manager: moveit_simple_con...
 * /move_group/moveit_manage_controllers: True
 * /move_group/octomap_frame: camera_rgb_optica...
 * /move_group/octomap_resolution: 0.05
 * /move_group/panda_arm/planner_configs: ['SBLkConfigDefau...
 * /move_group/panda_arm_hand/planner_configs: ['SBLkConfigDefau...
 * /move_group/planner_configs/BFMTkConfigDefault/balanced: 0
 * /move_group/planner_configs/BFMTkConfigDefault/cache_cc: 1
 * /move_group/planner_configs/BFMTkConfigDefault/extended_fmt: 1
 * /move_group/planner_configs/BFMTkConfigDefault/heuristics: 1
 * /move_group/planner_configs/BFMTkConfigDefault/nearest_k: 1
 * /move_group/planner_configs/BFMTkConfigDefault/num_samples: 1000
 * /move_group/planner_configs/BFMTkConfigDefault/optimality: 1
 * /move_group/planner_configs/BFMTkConfigDefault/radius_multiplier: 1.0
 * /move_group/planner_configs/BFMTkConfigDefault/type: geometric::BFMT
 * /move_group/planner_configs/BKPIECEkConfigDefault/border_fraction: 0.9
 * /move_group/planner_configs/BKPIECEkConfigDefault/failed_expansion_score_factor: 0.5
 * /move_group/planner_configs/BKPIECEkConfigDefault/min_valid_path_fraction: 0.5
 * /move_group/planner_configs/BKPIECEkConfigDefault/range: 0.0
 * /move_group/planner_configs/BKPIECEkConfigDefault/type: geometric::BKPIECE
 * /move_group/planner_configs/BiESTkConfigDefault/range: 0.0
 * /move_group/planner_configs/BiESTkConfigDefault/type: geometric::BiEST
 * /move_group/planner_configs/BiTRRTkConfigDefault/cost_threshold: 1e300
 * /move_group/planner_configs/BiTRRTkConfigDefault/frountier_node_ratio: 0.1
 * /move_group/planner_configs/BiTRRTkConfigDefault/frountier_threshold: 0.0
 * /move_group/planner_configs/BiTRRTkConfigDefault/init_temperature: 100
 * /move_group/planner_configs/BiTRRTkConfigDefault/range: 0.0
 * /move_group/planner_configs/BiTRRTkConfigDefault/temp_change_factor: 0.1
 * /move_group/planner_configs/BiTRRTkConfigDefault/type: geometric::BiTRRT
 * /move_group/planner_configs/ESTkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/ESTkConfigDefault/range: 0.0
 * /move_group/planner_configs/ESTkConfigDefault/type: geometric::EST
 * /move_group/planner_configs/FMTkConfigDefault/cache_cc: 1
 * /move_group/planner_configs/FMTkConfigDefault/extended_fmt: 1
 * /move_group/planner_configs/FMTkConfigDefault/heuristics: 0
 * /move_group/planner_configs/FMTkConfigDefault/nearest_k: 1
 * /move_group/planner_configs/FMTkConfigDefault/num_samples: 1000
 * /move_group/planner_configs/FMTkConfigDefault/radius_multiplier: 1.1
 * /move_group/planner_configs/FMTkConfigDefault/type: geometric::FMT
 * /move_group/planner_configs/KPIECEkConfigDefault/border_fraction: 0.9
 * /move_group/planner_configs/KPIECEkConfigDefault/failed_expansion_score_factor: 0.5
 * /move_group/planner_configs/KPIECEkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/KPIECEkConfigDefault/min_valid_path_fraction: 0.5
 * /move_group/planner_configs/KPIECEkConfigDefault/range: 0.0
 * /move_group/planner_configs/KPIECEkConfigDefault/type: geometric::KPIECE
 * /move_group/planner_configs/LBKPIECEkConfigDefault/border_fraction: 0.9
 * /move_group/planner_configs/LBKPIECEkConfigDefault/min_valid_path_fraction: 0.5
 * /move_group/planner_configs/LBKPIECEkConfigDefault/range: 0.0
 * /move_group/planner_configs/LBKPIECEkConfigDefault/type: geometric::LBKPIECE
 * /move_group/planner_configs/LBTRRTkConfigDefault/epsilon: 0.4
 * /move_group/planner_configs/LBTRRTkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/LBTRRTkConfigDefault/range: 0.0
 * /move_group/planner_configs/LBTRRTkConfigDefault/type: geometric::LBTRRT
 * /move_group/planner_configs/LazyPRMkConfigDefault/range: 0.0
 * /move_group/planner_configs/LazyPRMkConfigDefault/type: geometric::LazyPRM
 * /move_group/planner_configs/LazyPRMstarkConfigDefault/type: geometric::LazyPR...
 * /move_group/planner_configs/PDSTkConfigDefault/type: geometric::PDST
 * /move_group/planner_configs/PRMkConfigDefault/max_nearest_neighbors: 10
 * /move_group/planner_configs/PRMkConfigDefault/type: geometric::PRM
 * /move_group/planner_configs/PRMstarkConfigDefault/type: geometric::PRMstar
 * /move_group/planner_configs/ProjESTkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/ProjESTkConfigDefault/range: 0.0
 * /move_group/planner_configs/ProjESTkConfigDefault/type: geometric::ProjEST
 * /move_group/planner_configs/RRTConnectkConfigDefault/range: 0.0
 * /move_group/planner_configs/RRTConnectkConfigDefault/type: geometric::RRTCon...
 * /move_group/planner_configs/RRTkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/RRTkConfigDefault/range: 0.0
 * /move_group/planner_configs/RRTkConfigDefault/type: geometric::RRT
 * /move_group/planner_configs/RRTstarkConfigDefault/delay_collision_checking: 1
 * /move_group/planner_configs/RRTstarkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/RRTstarkConfigDefault/range: 0.0
 * /move_group/planner_configs/RRTstarkConfigDefault/type: geometric::RRTstar
 * /move_group/planner_configs/SBLkConfigDefault/range: 0.0
 * /move_group/planner_configs/SBLkConfigDefault/type: geometric::SBL
 * /move_group/planner_configs/SPARSkConfigDefault/dense_delta_fraction: 0.001
 * /move_group/planner_configs/SPARSkConfigDefault/max_failures: 1000
 * /move_group/planner_configs/SPARSkConfigDefault/sparse_delta_fraction: 0.25
 * /move_group/planner_configs/SPARSkConfigDefault/stretch_factor: 3.0
 * /move_group/planner_configs/SPARSkConfigDefault/type: geometric::SPARS
 * /move_group/planner_configs/SPARStwokConfigDefault/dense_delta_fraction: 0.001
 * /move_group/planner_configs/SPARStwokConfigDefault/max_failures: 5000
 * /move_group/planner_configs/SPARStwokConfigDefault/sparse_delta_fraction: 0.25
 * /move_group/planner_configs/SPARStwokConfigDefault/stretch_factor: 3.0
 * /move_group/planner_configs/SPARStwokConfigDefault/type: geometric::SPARStwo
 * /move_group/planner_configs/STRIDEkConfigDefault/degree: 16
 * /move_group/planner_configs/STRIDEkConfigDefault/estimated_dimension: 0.0
 * /move_group/planner_configs/STRIDEkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/STRIDEkConfigDefault/max_degree: 18
 * /move_group/planner_configs/STRIDEkConfigDefault/max_pts_per_leaf: 6
 * /move_group/planner_configs/STRIDEkConfigDefault/min_degree: 12
 * /move_group/planner_configs/STRIDEkConfigDefault/min_valid_path_fraction: 0.2
 * /move_group/planner_configs/STRIDEkConfigDefault/range: 0.0
 * /move_group/planner_configs/STRIDEkConfigDefault/type: geometric::STRIDE
 * /move_group/planner_configs/STRIDEkConfigDefault/use_projected_distance: 0
 * /move_group/planner_configs/TRRTkConfigDefault/frountierNodeRatio: 0.1
 * /move_group/planner_configs/TRRTkConfigDefault/frountier_threshold: 0.0
 * /move_group/planner_configs/TRRTkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/TRRTkConfigDefault/init_temperature: 10e-6
 * /move_group/planner_configs/TRRTkConfigDefault/k_constant: 0.0
 * /move_group/planner_configs/TRRTkConfigDefault/max_states_failed: 10
 * /move_group/planner_configs/TRRTkConfigDefault/min_temperature: 10e-10
 * /move_group/planner_configs/TRRTkConfigDefault/range: 0.0
 * /move_group/planner_configs/TRRTkConfigDefault/temp_change_factor: 2.0
 * /move_group/planner_configs/TRRTkConfigDefault/type: geometric::TRRT
 * /move_group/planner_configs/TrajOptDefault/type: geometric::TrajOpt
 * /move_group/planning_plugin: ompl_interface/OM...
 * /move_group/planning_scene_monitor/publish_geometry_updates: True
 * /move_group/planning_scene_monitor/publish_planning_scene: True
 * /move_group/planning_scene_monitor/publish_state_updates: True
 * /move_group/planning_scene_monitor/publish_transforms_updates: True
 * /move_group/request_adapters: default_planner_r...
 * /move_group/sensors: [{'point_subsampl...
 * /move_group/start_state_max_bounds_error: 0.1
 * /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
 * /robot_description_kinematics/panda_arm/kinematics_solver: kdl_kinematics_pl...
 * /robot_description_kinematics/panda_arm/kinematics_solver_search_resolution: 0.005
 * /robot_description_kinematics/panda_arm/kinematics_solver_timeout: 0.05
 * /robot_description_planning/joint_limits/panda_finger_joint1/has_acceleration_limits: False
 * /robot_description_planning/joint_limits/panda_finger_joint1/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_finger_joint1/max_acceleration: 0
 * /robot_description_planning/joint_limits/panda_finger_joint1/max_velocity: 0.1
 * /robot_description_planning/joint_limits/panda_finger_joint2/has_acceleration_limits: False
 * /robot_description_planning/joint_limits/panda_finger_joint2/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_finger_joint2/max_acceleration: 0
 * /robot_description_planning/joint_limits/panda_finger_joint2/max_velocity: 0.1
 * /robot_description_planning/joint_limits/panda_joint1/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint1/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint1/max_acceleration: 3.75
 * /robot_description_planning/joint_limits/panda_joint1/max_velocity: 2.175
 * /robot_description_planning/joint_limits/panda_joint2/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint2/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint2/max_acceleration: 1.875
 * /robot_description_planning/joint_limits/panda_joint2/max_velocity: 2.175
 * /robot_description_planning/joint_limits/panda_joint3/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint3/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint3/max_acceleration: 2.5
 * /robot_description_planning/joint_limits/panda_joint3/max_velocity: 2.175
 * /robot_description_planning/joint_limits/panda_joint4/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint4/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint4/max_acceleration: 3.125
 * /robot_description_planning/joint_limits/panda_joint4/max_velocity: 2.175
 * /robot_description_planning/joint_limits/panda_joint5/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint5/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint5/max_acceleration: 3.75
 * /robot_description_planning/joint_limits/panda_joint5/max_velocity: 2.61
 * /robot_description_planning/joint_limits/panda_joint6/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint6/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint6/max_acceleration: 5
 * /robot_description_planning/joint_limits/panda_joint6/max_velocity: 2.61
 * /robot_description_planning/joint_limits/panda_joint7/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint7/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint7/max_acceleration: 5
 * /robot_description_planning/joint_limits/panda_joint7/max_velocity: 2.61
 * /robot_description_semantic: <?xml version="1....
 * /rosdistro: melodic
 * /rosversion: 1.14.12

NODES
  /
    move_group (moveit_ros_move_group/move_group)

ROS_MASTER_URI=http://localhost:11311

process[move_group-1]: started with pid [24707]
[ INFO] [1639336661.722669740]: Loading robot model 'panda'...
[ WARN] [1639336661.723193547]: Skipping virtual joint 'virtual_joint' because its child frame 'panda_link0' does not match the URDF frame 'world'
[ INFO] [1639336661.723208606]: No root/virtual joint specified in SRDF. Assuming fixed joint
[ INFO] [1639336661.792941875]: Publishing maintained planning scene on 'monitored_planning_scene'
[ INFO] [1639336661.794307730]: MoveGroup debug mode is OFF
Starting planning scene monitors...
[ INFO] [1639336661.794329327]: Starting planning scene monitor
[ INFO] [1639336661.795594958]: Listening to '/planning_scene'
[ INFO] [1639336661.795611253]: Starting world geometry update monitor for collision objects, attached objects, octomap updates.
[ INFO] [1639336661.796827074]: Listening to '/collision_object'
[ INFO] [1639336661.798191450]: Listening to '/planning_scene_world' for planning scene world geometry
[ INFO] [1639336661.812007300]: Listening to '/camera/depth_registered/points' using message filter with target frame 'world '
[ INFO] [1639336661.814709994]: Listening to '/attached_collision_object' for attached collision objects
Planning scene monitors started.
[ INFO] [1639336661.834285270]: Initializing OMPL interface using ROS parameters
[ INFO] [1639336661.856712744]: Using planning interface 'OMPL'
[ INFO] [1639336661.858624607]: Param 'default_workspace_bounds' was not set. Using default value: 10
[ INFO] [1639336661.858897173]: Param 'start_state_max_bounds_error' was set to 0.1
[ INFO] [1639336661.859087916]: Param 'start_state_max_dt' was not set. Using default value: 0.5
[ INFO] [1639336661.859319533]: Param 'start_state_max_dt' was not set. Using default value: 0.5
[ INFO] [1639336661.859650751]: Param 'jiggle_fraction' was set to 0.05
[ INFO] [1639336661.859897447]: Param 'max_sampling_attempts' was not set. Using default value: 100
[ERROR] [1639336661.860011144]: Exception while loading planning adapter plugin 'default_planner_request_adapters/ResolveConstraintFrames': According to the loaded plugin descriptions the class default_planner_request_adapters/ResolveConstraintFrames with base class type planning_request_adapter::PlanningRequestAdapter does not exist. Declared types are  default_planner_request_adapters/AddIterativeSplineParameterization default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/AddTimeParameterization default_planner_request_adapters/Empty default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints default_planner_request_adapters/FixWorkspaceBounds industrial_trajectory_filters/AddSmoothingFilter industrial_trajectory_filters/NPointFilter industrial_trajectory_filters/UniformSampleFilter
[ INFO] [1639336661.860059915]: Using planning request adapter 'Fix Workspace Bounds'
[ INFO] [1639336661.860075829]: Using planning request adapter 'Fix Start State Bounds'
[ INFO] [1639336661.860088856]: Using planning request adapter 'Fix Start State In Collision'
[ INFO] [1639336661.860102397]: Using planning request adapter 'Fix Start State Path Constraints'
[ INFO] [1639336661.860115270]: Using planning request adapter 'Add Time Parameterization'
[ WARN] [1639336666.975225268, 12.872000000]: Waiting for position_joint_trajectory_controller/follow_joint_trajectory to come up
[ WARN] [1639336673.001382031, 18.872000000]: Waiting for position_joint_trajectory_controller/follow_joint_trajectory to come up
[ERROR] [1639336679.026824715, 24.873000000]: Action client not connected: position_joint_trajectory_controller/follow_joint_trajectory
[ INFO] [1639336679.378237921, 25.222000000]: Added GripperCommand controller for franka_gripper
[ INFO] [1639336679.378424088, 25.222000000]: Returned 1 controllers in list
[ INFO] [1639336679.411066354, 25.255000000]: Trajectory execution is managing controllers
Loading 'move_group/ApplyPlanningSceneService'...
Loading 'move_group/ClearOctomapService'...
Loading 'move_group/MoveGroupCartesianPathService'...
Loading 'move_group/MoveGroupExecuteTrajectoryAction'...
Loading 'move_group/MoveGroupGetPlanningSceneService'...
Loading 'move_group/MoveGroupKinematicsService'...
Loading 'move_group/MoveGroupMoveAction'...
Loading 'move_group/MoveGroupPickPlaceAction'...
Loading 'move_group/MoveGroupPlanService'...
Loading 'move_group/MoveGroupQueryPlannersService'...
Loading 'move_group/MoveGroupStateValidationService'...
[ INFO] [1639336679.555536101, 25.399000000]: 

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

[ INFO] [1639336679.555641741, 25.399000000]: MoveGroup context using planning plugin ompl_interface/OMPLPlanner
[ INFO] [1639336679.555686856, 25.399000000]: MoveGroup context initialization complete

You can start planning now!

ImportError: No module named quaternion [joint_trajectory_server_emulator-11] process has died

I am facing another problem that when I run the command roslaunch panda_gazebo panda_world.launch
, the terminal will report ImportError: No module named quaternion [joint_trajectory_server_emulator-11] process has died [pid 15370, exit code 1, cmd /home/ye/finalyearproject/src/panda_simulator/panda_sim_custom_action_server/scripts/start_joint_trajectory_server.py __name:=joint_trajectory_server_emulator __log:=/home/ye/.ros/log/ec2ff2f2-9d96-11eb-9889-000c294926c2/joint_trajectory_server_emulator-11.log]. log file: /home/ye/.ros/log/ec2ff2f2-9d96-11eb-9889-000c294926c2/joint_trajectory_server_emulator-11*.log

When I run the command roslaunch panda_simulator_examples demo_moveit.launch, it will report
[rviz_ubuntu_14368_8967066934926071941-15] process has died [pid 14434, exit code 127, cmd /opt/ros/melodic/lib/rviz/rviz -d /home/ye/finalyearproject/src/franka_ros_interface/franka_moveit/config/moveit_demo.rviz __name:=rviz_ubuntu_14368_8967066934926071941 __log:=/home/ye/.ros/log/6bd8cce6-9d96-11eb-9889-000c294926c2/rviz_ubuntu_14368_8967066934926071941-15.log]. log file: /home/ye/.ros/log/6bd8cce6-9d96-11eb-9889-000c294926c2/rviz_ubuntu_14368_8967066934926071941-15*.log and the window of rviz disappeared as soon as it appears. Now I could see the robot model in gazebo but I could not do anything

I have catkin build all the workspace and it succeeded. But there is three ignored packages. Maybe the building of franka_ros_interface is wrong but it doesn't tell anything from catkin build

`ye@ubuntu:~/finalyearproject$ catkin build

Profile: default
Extending: [cached] /opt/ros/melodic
Workspace: /home/ye/finalyearproject

Build Space: [exists] /home/ye/finalyearproject/build
Devel Space: [exists] /home/ye/finalyearproject/devel
Install Space: [unused] /home/ye/finalyearproject/install
Log Space: [exists] /home/ye/finalyearproject/logs
Source Space: [exists] /home/ye/finalyearproject/src
DESTDIR: [unused] None

Devel Space Layout: linked
Install Space Layout: None

Additional CMake Args: None
Additional Make Args: None
Additional catkin Make Args: None
Internal Make Job Server: True
Cache Job Environments: False

Whitelisted Packages: None
Blacklisted Packages: None

Workspace configuration appears valid.

[build] Found '22' packages in 0.0 seconds.
[build] Updating package table.
Starting >>> communication
Starting >>> franka_core_msgs
Starting >>> franka_moveit
Starting >>> franka_panda_description
Starting >>> fyp
Starting >>> orocos_kdl
Finished <<< fyp [ 0.1 seconds ]
Starting >>> panda_hardware_interface
Finished <<< franka_panda_description [ 0.1 seconds ]
Starting >>> panda_sim_moveit
Finished <<< panda_hardware_interface [ 0.1 seconds ]
Starting >>> push
Finished <<< orocos_kdl [ 0.2 seconds ]
Finished <<< panda_sim_moveit [ 0.1 seconds ]
Finished <<< communication [ 0.5 seconds ]
Starting >>> turtlebot3_fake
Starting >>> turtlebot3_gazebo
Starting >>> python_orocos_kdl
Finished <<< push [ 0.1 seconds ]
Finished <<< python_orocos_kdl [ 0.1 seconds ]
Finished <<< franka_moveit [ 0.9 seconds ]
Finished <<< turtlebot3_fake [ 0.4 seconds ]
Finished <<< turtlebot3_gazebo [ 0.5 seconds ]
Finished <<< franka_core_msgs [ 1.6 seconds ]
Starting >>> franka_interface
Starting >>> franka_ros_controllers
Starting >>> panda_sim_controllers
Finished <<< panda_sim_controllers [ 7.2 seconds ]
Finished <<< franka_ros_controllers [ 15.4 seconds ]
Finished <<< franka_interface [ 20.1 seconds ]
Starting >>> franka_tools
Starting >>> panda_sim_custom_action_server
Finished <<< panda_sim_custom_action_server [ 0.1 seconds ]
Finished <<< franka_tools [ 1.1 seconds ]
Starting >>> panda_gazebo
Finished <<< panda_gazebo [ 8.5 seconds ]
Starting >>> panda_simulator_examples
Finished <<< panda_simulator_examples [ 0.1 seconds ]
[build] Summary: All 19 packages succeeded!
[build] Ignored: 3 packages were skipped or are blacklisted.
[build] Warnings: None.
[build] Abandoned: None.
[build] Failed: None.
[build] Runtime: 31.7 seconds total.`

Launch crashes with protobuf error.

Hi There,

Thank you for this code and the repo.

I was able to build this repo. But when I try to launch roslaunch panda_gazebo panda_world.launch, I get the following error and the launch crashes. I am using another robots with Gazebo and it works fine. I am using ROS melodic with Gazebo 9. By Default, Gazebo needs protoc 3.0.0, which is also system installed. If I install 3.14 then the program does not compile. Any insights on this issue will be very helpful.

Thanks a ton!

[ INFO] [1606816804.851503670, 0.020000000]: waitForService: Service [/gazebo/set_physics_properties] is now available. [ INFO] [1606816804.867844528, 0.035000000]: Physics dynamic reconfigure ready. [ INFO] [1606816805.088884166, 0.153000000]: Loading gazebo_ros_control plugin [ INFO] [1606816805.091071827, 0.153000000]: Starting gazebo_ros_control plugin in namespace: [ INFO] [1606816805.091505893, 0.153000000]: gazebo_ros_control plugin is waiting for model URDF in parameter [/robot_description] on the ROS param server.

[libprotobuf FATAL google/protobuf/stubs/common.cc:67] This program requires version 3.14.0 of the Protocol Buffer runtime library, but the installed version is 3.0.0. Please update your library. If you compiled the program yourself, make sure that your headers are from the same version of Protocol Buffers as your link-time library. (Version verification failed in "google/protobuf/any.pb.cc".) terminate called after throwing an instance of 'google::protobuf::FatalException'

what(): This program requires version 3.14.0 of the Protocol Buffer runtime library, but the installed version is 3.0.0. Please update your library. If you compiled the program yourself, make sure that your headers are from the same version of Protocol Buffers as your link-time library. (Version verification failed in "google/protobuf/any.pb.cc".) Aborted (core dumped)

[gazebo-1] process has died [pid 31958, exit code 134, cmd /opt/ros/melodic/lib/gazebo_ros/gzserver -e ode /home/padmaja/ros/src/panda_simulator/panda_gazebo/worlds/panda.world __name:=gazebo __log:=/home/padmaja/.ros/log/a9a6cd74-33bb-11eb-8c49-50e085401a14/gazebo-1.log]. log file: /home/padmaja/.ros/log/a9a6cd74-33bb-11eb-8c49-50e085401a14/gazebo-1*.log

[ERROR] [1606816806.069719, 0.153000]: SetModelConfiguration service failed. Exiting.

[robot_description-3] process has died [pid 31966, exit code 1, cmd /opt/ros/melodic/lib/gazebo_ros/spawn_model -param robot_description -urdf -model panda -J panda::panda_joint1 0.000 -J panda::panda_joint2 -0.785 -J panda::panda_joint3 0.0 -J panda::panda_joint4 -2.356 -J panda::panda_joint5 0.0 -J panda::panda_joint6 1.57 -J panda::panda_joint7 0.785 __name:=robot_description __log:=/home/padmaja/.ros/log/a9a6cd74-33bb-11eb-8c49-50e085401a14/robot_description-3.log]. log file: /home/padmaja/.ros/log/a9a6cd74-33bb-11eb-8c49-50e085401a14/robot_description-3*.log

Error when executing move_robot.py

Hello,

I followed all the installation steps and i do the following:

1st shell: $ roslaunch panda_gazebo panda_world.launch
2nd shell: cd ~/catkin_ws/src/panda_simulator/panda_simulator_examples/scripts and $ python move_robot.py.

I get the following error:

Traceback (most recent call last):
  File "move_robot.py", line 4, in <module>
    from franka_core_msgs.msg import JointCommand, RobotState
ImportError: No module named franka_core_msgs.msg 

P.S.
At the beginning i was getting an error when launching the panda_world.launch:
[ERROR] [1585070496.558123479, 0.613000000]: Could not load controller 'panda_simulator/joint_state_controller' because controller type 'joint_state_controller/JointStateController' does not exist.
now it works because i did the following (is it wrong?): sudo apt-get install ros-melodic-joint-state-controller
Thanks

Build fails on melodic

Hi,

Great work on the simulator, I was trying to build the package and saw the following error. There seems to be a library file missing. Not really sure what I am doing wrong. Any help would be great.

/catkin_ws/src/franka_ros_interface/franka_interface/src/franka_control_node.cpp:44:10: fatal error: franka_control/ErrorRecoveryAction.h: No such file or directory
#include <franka_control/ErrorRecoveryAction.h>
^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
compilation terminated.
make[2]: *** [CMakeFiles/custom_franka_control_node.dir/src/franka_control_node.cpp.o] Error 1
make[1]: *** [CMakeFiles/custom_franka_control_node.dir/all] Error 2
make: *** [all] Error 2

Robot is moving in Gazebo when no controller is started

I want to use this package for testing my own ros_control plugins before running them on the real robot.

As the custom panda_gazebo_ros_control_plugin does not seem to provide a working EffortJointInterface (#25), I modified the panda_world.launch file so that

<param name="robot_description" command="$(find xacro)/xacro --inorder $(find franka_panda_description)/robots/panda_arm_hand.urdf.xacro load_gripper:=$(arg load_gripper) load_gazebo:=$(arg load_gazebo)"/>

becomes

<param name="robot_description" command="$(find xacro)/xacro --inorder $(find franka_panda_description)/robots/panda_arm_hand.urdf.xacro load_gripper:=$(arg load_gripper) load_gazebo:=$(arg load_gazebo) use_gazebo_control:=true"/>

Now instead of the custom panda_gazebo_ros_control_plugin the default gazebo control is loaded. The EffortJointInterface now works as expected, after Gazebo gets initialized and before the controller is loaded robot moves weirdly. Wouldn't it be expected that the robot stays still before any controller is initialized?

Installation issue with panda_simulator

As required, I git clone panda_simulator, franka_panda_description, franka_ros_interface and orocos_kinematics_dynamics from github web pages into my workspace. When I catkin_make my workspace, there's an error shown as below,

at /opt/ros/melodic/share/catkin/cmake/catkin_workspace.cmake:100 (message):
This workspace contains non-catkin packages in it, and catkin cannot build
a non-homogeneous workspace without isolation. Try the
'catkin_make_isolated' command instead.
Call Stack (most recent call first):
CMakeLists.txt:69 (catkin_workspace)

-- Configuring incomplete, errors occurred!
See also "/home/george/ws_franka/build/CMakeFiles/CMakeOutput.log".
See also "/home/george/ws_franka/build/CMakeFiles/CMakeError.log".
Invoking "cmake" failed

I am not sure how to figure this out. Hopefully, this can be explained.

Dual-arm Simulation using PandaRobotHWSim

Hello, thank you very much for your work!

I'm trying to set up a dual-arm simulation environment using the PandaRobotHWSim interface but cannot find a convenient way to configure different namespaces for the controllers and the topics. According to the source code of the plugin, it seems that the namespace of the controller is somehow hard-coded and cannot be modified. Could you please provide some advice if possible? Thank you very much in advance.

Dependency to Quaternion

Both action servers can't start because of missing dependency

  File "/home/romzn/workspaces/panda_demonstrator/src/franka_ros_interface/franka_interface/src/franka_interface/arm.py", line 37, in <module>
    import quaternion
ImportError: No module named quaternion
[ INFO] [1601634944.600077933]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1601634944.601498619]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting...
[gripper_action_server_emulator-13] process has died [pid 11961, exit code 1, cmd /home/romzn/workspaces/panda_demonstrator/src/panda_simulator/panda_sim_custom_action_server/scripts/start_gripper_action_server.py __name:=gripper_action_server_emulator __log:=/home/romzn/.ros/log/05ba3cc2-049b-11eb-97a0-347df65a3075/gripper_action_server_emulator-13.log].
log file: /home/romzn/.ros/log/05ba3cc2-049b-11eb-97a0-347df65a3075/gripper_action_server_emulator-13*.log

Solved with pip install numpy-quaternion

I use cpp to imitate python script(move_robot.py). message md5sum is mismatch.

I copied some .msg files from franka_ros_interface\franka_common\franka_core_msgs\msg to my package(panda_sim_testcpp) panda_sim_testcpp\msg.
and I change package.xml, CMakeList.txt to configure it.
it occured error. because it missed some dependencies.
so, I copied franka_ros\franka_msgs this package to my catkin workspace.
it. after that, I added package dependency.
<build_depend>franka_msgs</build_depend> <exec_depend>franka_msgs</exec_depend>
now, compile successed.
i quiet sure about my cpp code correct. and i ran my node get errors. goes with md5sum is mismatch.

[ERROR] [1619424870.047841513]: md5sum mismatch making local subscription to topic /panda_simulator/motion_controller/arm/joint_commands.
[ERROR] [1619424870.050563349]: Subscriber expects type sensor_msgs/JointState, md5sum 3066dcd76a6cfaef579bd0f34173e9fd
[ERROR] [1619424870.050673424]: Publisher provides type panda_sim_testcpp/JointCommand, md5sum 766f72e801d6180a86db23dbf2c2a56f

how can i generate right header. could u give me some advice? I also want to know the right message md5.

Errors when running `roslaunch panda_gazebo panda_world.launch`

Starting roslaunch panda_gazebo panda_world.launch makes the program run gazebo, but there are still errors showing up:

[gripper_action_server_emulator-13] process has died [pid 1825, exit code 1, cmd /home/vm-ros/catkin_ws/src/panda_simulator/panda_sim_custom_action_server/scripts/start_gripper_action_server.py __name:=gripper_action_server_emulator __log:=/home/vm-ros/.ros/log/1679ce04-4d30-11ec-81fb-000c299c877b/gripper_action_server_emulator-13.log]. log file: /home/vm-ros/.ros/log/1679ce04-4d30-11ec-81fb-000c299c877b/gripper_action_server_emulator-13*.log

[joint_trajectory_server_emulator-12] process has died [pid 1818, exit code 1, cmd /home/vm-ros/catkin_ws/src/panda_simulator/panda_sim_custom_action_server/scripts/start_joint_trajectory_server.py __name:=joint_trajectory_server_emulator __log:=/home/vm-ros/.ros/log/1679ce04-4d30-11ec-81fb-000c299c877b/joint_trajectory_server_emulator-12.log]. log file: /home/vm-ros/.ros/log/1679ce04-4d30-11ec-81fb-000c299c877b/joint_trajectory_server_emulator-12*.log

Invoking "cmake" failed

HI! I am following your instructions to catkin_make panda_simulator
I used franka_ros 0.6.0; panda_simulator kinetic-devel, libranka 0.7.0
When I catkin_make:

-- ~~ traversing 17 packages in topological order:
-- ~~ - franka_panda_description
-- ~~ - franka_ros_interface (metapackage)
-- ~~ - orocos_kdl (plain cmake)
-- ~~ - orocos_kinematics_dynamics
-- ~~ - panda_simulator (metapackage)
-- ~~ - python_orocos_kdl (plain cmake)
-- ~~ - panda_hardware_interface
-- ~~ - franka_core_msgs
-- ~~ - panda_sim_controllers
-- ~~ - franka_interface
-- ~~ - franka_ros_controllers
-- ~~ - franka_moveit
-- ~~ - franka_tools
-- ~~ - panda_sim_custom_action_server
-- ~~ - panda_gazebo
-- ~~ - panda_sim_moveit
-- ~~ - panda_simulator_examples
-- ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
CMake Error at /opt/ros/kinetic/share/catkin/cmake/catkin_workspace.cmake:95 (message):
This workspace contains non-catkin packages in it, and catkin cannot build
a non-homogeneous workspace without isolation. Try the
'catkin_make_isolated' command instead.
Call Stack (most recent call first):
CMakeLists.txt:67 (catkin_workspace)

Thanks!

[gripper_action_server_emulator-12] process has died

Hey, I tried to run:
$ roslaunch panda_gazebo panda_world.launch start_moveit:=false

It can generate the robot in the gazebo successfully, however, with these errors:
[gripper_action_server_emulator-12] process has died [pid 12790, exit code 1, cmd /home/sission/workspace/src/panda_simulator/panda_sim_custom_action_server/scripts/start_gripper_action_server.py __name:=gripper_action_server_emulator __log:=/home/sission/.ros/log/5c634612-1e05-11eb-801a-049226c26561/gripper_action_server_emulator-12.log].
log file: /home/sission/.ros/log/5c634612-1e05-11eb-801a-049226c26561/gripper_action_server_emulator-12*.log

[joint_trajectory_server_emulator-11] process has died [pid 12782, exit code 1, cmd /home/sission/workspace/src/panda_simulator/panda_sim_custom_action_server/scripts/start_joint_trajectory_server.py __name:=joint_trajectory_server_emulator __log:=/home/sission/.ros/log/5c634612-1e05-11eb-801a-049226c26561/joint_trajectory_server_emulator-11.log].
log file: /home/sission/.ros/log/5c634612-1e05-11eb-801a-049226c26561/joint_trajectory_server_emulator-11*.log

Also, the generated robot seems to have uncorrect gravity (not the pose you shown in the gif)

Issue with set of controllers in Kinetic

Hi, we try to use the MoveIt demo, on Kinetic, but we get an error:

[ERROR] [1604587753.964362125, 179.575000000]: Unable to identify any set of controllers that can actuate the specified joints: [ panda_joint1 panda_joint2 panda_joint3 panda_joint4 panda_joint5 panda_joint6 panda_joint7 ]
[ERROR] [1604587753.964425957, 179.575000000]: Known controllers and their joints:

[ERROR] [1604587753.964546268, 179.575000000]: Apparently trajectory initialization failed

Getting Segmentation Fault while lanuching the panda_world.launch file

I am continuously getting the error of segmentation fault while launching the panda_world.launch file and could not spawn the robot.

Can anyone please guide me on how can I solve this issue?

Error Log :

apanrtx@apanrtx:~$ roslaunch panda_gazebo panda_world.launch
... logging to /home/apanrtx/.ros/log/a2a1954a-5fc0-11ec-8a29-04d4c45b62cf/roslaunch-apanrtx-12593.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

xacro: in-order processing became default in ROS Melodic. You can drop the option.
started roslaunch server http://apanrtx:38245/

SUMMARY

PARAMETERS

  • /SIMULATOR_: True
  • /arm/gravity_tip_name: panda_hand
  • /arm/root_name: panda_link0
  • /arm/tip_name: panda_hand
  • /controllers_config/default_controller: panda_simulator/p...
  • /controllers_config/position_controller: panda_simulator/p...
  • /controllers_config/torque_controller: panda_simulator/e...
  • /controllers_config/velocity_controller: panda_simulator/v...
  • /franka_gripper/robot_ip: sim
  • /gazebo/enable_ros_network: True
  • /gripper_config/default_grasp_epsilon/inner: 0.005
  • /gripper_config/default_grasp_epsilon/outer: 0.005
  • /gripper_config/default_speed: 0.1
  • /gripper_config/joint_names: ['panda_finger_jo...
  • /panda_simulator/effort_joint_gravity_controller/joints/panda_joint1_controller/joint: panda_joint1
  • /panda_simulator/effort_joint_gravity_controller/joints/panda_joint2_controller/joint: panda_joint2
  • /panda_simulator/effort_joint_gravity_controller/joints/panda_joint3_controller/joint: panda_joint3
  • /panda_simulator/effort_joint_gravity_controller/joints/panda_joint4_controller/joint: panda_joint4
  • /panda_simulator/effort_joint_gravity_controller/joints/panda_joint5_controller/joint: panda_joint5
  • /panda_simulator/effort_joint_gravity_controller/joints/panda_joint6_controller/joint: panda_joint6
  • /panda_simulator/effort_joint_gravity_controller/joints/panda_joint7_controller/joint: panda_joint7
  • /panda_simulator/effort_joint_gravity_controller/type: panda_sim_control...
  • /panda_simulator/effort_joint_torque_controller/joints/panda_joint1_controller/joint: panda_joint1
  • /panda_simulator/effort_joint_torque_controller/joints/panda_joint2_controller/joint: panda_joint2
  • /panda_simulator/effort_joint_torque_controller/joints/panda_joint3_controller/joint: panda_joint3
  • /panda_simulator/effort_joint_torque_controller/joints/panda_joint4_controller/joint: panda_joint4
  • /panda_simulator/effort_joint_torque_controller/joints/panda_joint5_controller/joint: panda_joint5
  • /panda_simulator/effort_joint_torque_controller/joints/panda_joint6_controller/joint: panda_joint6
  • /panda_simulator/effort_joint_torque_controller/joints/panda_joint7_controller/joint: panda_joint7
  • /panda_simulator/effort_joint_torque_controller/topic: /panda_simulator/...
  • /panda_simulator/effort_joint_torque_controller/type: panda_sim_control...
  • /panda_simulator/joint_state_controller/publish_rate: 100
  • /panda_simulator/joint_state_controller/type: joint_state_contr...
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/joint: panda_finger_joint1
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/d: 0.5
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/i: 50
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/p: 5000
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/joint: panda_finger_joint2
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/d: 0.5
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/i: 50
  • /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/p: 5000
  • /panda_simulator/panda_gripper_controller/pub_topic: /franka_gripper/j...
  • /panda_simulator/panda_gripper_controller/type: panda_sim_control...
  • /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/joint: panda_joint1
  • /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/d: 25.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/i: 10.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/p: 3000
  • /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/joint: panda_joint2
  • /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/d: 30.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/i: 10.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/p: 3000
  • /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/joint: panda_joint3
  • /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/d: 30.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/i: 10.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/p: 3000
  • /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/joint: panda_joint4
  • /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/d: 50.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/i: 10.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/p: 3000
  • /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/joint: panda_joint5
  • /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/d: 8.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/i: 10.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/p: 3000
  • /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/joint: panda_joint6
  • /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/d: 5.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/i: 1.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/p: 3000
  • /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/joint: panda_joint7
  • /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/d: 4.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/i: 10.0
  • /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/p: 3000
  • /panda_simulator/position_joint_position_controller/topic_joint_command: /panda_simulator/...
  • /panda_simulator/position_joint_position_controller/topic_set_speed_ratio: /panda_simulator/...
  • /panda_simulator/position_joint_position_controller/type: panda_sim_control...
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/joint: panda_joint1
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/d: 0.1
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/i: 0.0
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/p: 10
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/joint: panda_joint2
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/d: 0.1
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/i: 1.0
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/p: 100
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/joint: panda_joint3
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/d: 0.01
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/i: 0.0
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/p: 0.05
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/joint: panda_joint4
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/d: 0.1
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/i: 0.01
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/p: 0.5
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/joint: panda_joint5
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/d: 0.01
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/i: 0.0
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/p: 1.0
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/joint: panda_joint6
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/d: 0.01
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/i: 0.0
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/p: 0.05
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/joint: panda_joint7
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/d: 0.01
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/i: 0.0
  • /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/p: 0.05
  • /panda_simulator/velocity_joint_velocity_controller/topic: /panda_simulator/...
  • /panda_simulator/velocity_joint_velocity_controller/type: panda_sim_control...
  • /robot_config/arm_id: panda
  • /robot_config/joint_config/joint_acceleration_limit/panda_joint1: 15.0
  • /robot_config/joint_config/joint_acceleration_limit/panda_joint2: 7.5
  • /robot_config/joint_config/joint_acceleration_limit/panda_joint3: 10.0
  • /robot_config/joint_config/joint_acceleration_limit/panda_joint4: 12.5
  • /robot_config/joint_config/joint_acceleration_limit/panda_joint5: 15.0
  • /robot_config/joint_config/joint_acceleration_limit/panda_joint6: 20.0
  • /robot_config/joint_config/joint_acceleration_limit/panda_joint7: 20.0
  • /robot_config/joint_config/joint_effort_limit/panda_joint1: 87
  • /robot_config/joint_config/joint_effort_limit/panda_joint2: 87
  • /robot_config/joint_config/joint_effort_limit/panda_joint3: 87
  • /robot_config/joint_config/joint_effort_limit/panda_joint4: 87
  • /robot_config/joint_config/joint_effort_limit/panda_joint5: 12
  • /robot_config/joint_config/joint_effort_limit/panda_joint6: 12
  • /robot_config/joint_config/joint_effort_limit/panda_joint7: 12
  • /robot_config/joint_config/joint_position_limit/lower/panda_joint1: -2.8973
  • /robot_config/joint_config/joint_position_limit/lower/panda_joint2: -1.7628
  • /robot_config/joint_config/joint_position_limit/lower/panda_joint3: -2.8973
  • /robot_config/joint_config/joint_position_limit/lower/panda_joint4: -3.0718
  • /robot_config/joint_config/joint_position_limit/lower/panda_joint5: -2.8973
  • /robot_config/joint_config/joint_position_limit/lower/panda_joint6: -0.0175
  • /robot_config/joint_config/joint_position_limit/lower/panda_joint7: -2.8973
  • /robot_config/joint_config/joint_position_limit/upper/panda_joint1: 2.8973
  • /robot_config/joint_config/joint_position_limit/upper/panda_joint2: 1.7628
  • /robot_config/joint_config/joint_position_limit/upper/panda_joint3: 2.8973
  • /robot_config/joint_config/joint_position_limit/upper/panda_joint4: -0.0698
  • /robot_config/joint_config/joint_position_limit/upper/panda_joint5: 2.8973
  • /robot_config/joint_config/joint_position_limit/upper/panda_joint6: 3.7525
  • /robot_config/joint_config/joint_position_limit/upper/panda_joint7: 2.8973
  • /robot_config/joint_config/joint_velocity_limit/panda_joint1: 2.175
  • /robot_config/joint_config/joint_velocity_limit/panda_joint2: 2.175
  • /robot_config/joint_config/joint_velocity_limit/panda_joint3: 2.175
  • /robot_config/joint_config/joint_velocity_limit/panda_joint4: 2.175
  • /robot_config/joint_config/joint_velocity_limit/panda_joint5: 2.61
  • /robot_config/joint_config/joint_velocity_limit/panda_joint6: 2.61
  • /robot_config/joint_config/joint_velocity_limit/panda_joint7: 2.61
  • /robot_config/joint_names: ['panda_joint1', ...
  • /robot_config/neutral_pose/panda_joint1: -0.0177920602278
  • /robot_config/neutral_pose/panda_joint2: -0.760123541104
  • /robot_config/neutral_pose/panda_joint3: 0.0197826070234
  • /robot_config/neutral_pose/panda_joint4: -2.34205014054
  • /robot_config/neutral_pose/panda_joint5: 0.0298405313558
  • /robot_config/neutral_pose/panda_joint6: 1.54119352986
  • /robot_config/neutral_pose/panda_joint7: 0.753448658975
  • /robot_description: <?xml version="1....
  • /rosdistro: melodic
  • /rosversion: 1.14.11
  • /use_sim_time: True

NODES
/
base_to_link0 (tf/static_transform_publisher)
controller_spawner (controller_manager/controller_manager)
controller_spawner_stopped (controller_manager/controller_manager)
gazebo (gazebo_ros/gzserver)
gazebo_gui (gazebo_ros/gzclient)
gripper_action_server_emulator (panda_sim_custom_action_server/start_gripper_action_server.py)
joint_trajectory_server_emulator (panda_sim_custom_action_server/start_joint_trajectory_server.py)
panda_gripper_controller_spawner_stopped (controller_manager/controller_manager)
robot_description (gazebo_ros/spawn_model)
robot_state_publisher (robot_state_publisher/robot_state_publisher)
startup_script (panda_gazebo/force_neutral_pose.py)
topic_remap (topic_tools/relay)
world_to_base (tf/static_transform_publisher)

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

setting /run_id to a2a1954a-5fc0-11ec-8a29-04d4c45b62cf
process[rosout-1]: started with pid [12679]
started core service [/rosout]
process[gazebo-2]: started with pid [12686]
process[gazebo_gui-3]: started with pid [12691]
process[robot_description-4]: started with pid [12698]
process[base_to_link0-5]: started with pid [12699]
process[world_to_base-6]: started with pid [12700]
process[controller_spawner-7]: started with pid [12708]
process[controller_spawner_stopped-8]: started with pid [12716]
process[panda_gripper_controller_spawner_stopped-9]: started with pid [12734]
process[robot_state_publisher-10]: started with pid [12753]
process[topic_remap-11]: started with pid [12774]
process[joint_trajectory_server_emulator-12]: started with pid [12793]
process[gripper_action_server_emulator-13]: started with pid [12829]
process[startup_script-14]: started with pid [12849]
[ INFO] [1639804152.700658662]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1639804152.702818228]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1639804152.716822570]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting...
[ INFO] [1639804152.717852851]: Finished loading Gazebo ROS API Plugin.
/home/apanrtx/.local/lib/python2.7/site-packages/quaternion/numba_wrapper.py:21: UserWarning:

!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
Could not import from numba, which means that some
parts of this code may run MUCH more slowly. You
may wish to install numba.
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

warnings.warn(warning_text)
/home/apanrtx/.local/lib/python2.7/site-packages/quaternion/numba_wrapper.py:21: UserWarning:

!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
Could not import from numba, which means that some
parts of this code may run MUCH more slowly. You
may wish to install numba.
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

warnings.warn(warning_text)
[ INFO] [1639804154.799223556]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1639804154.873947283]: Physics dynamic reconfigure ready.
[ INFO] [1639804155.396664153]: ft_sensor plugin reporting wrench values to the frame [panda_link7]
[ INFO] [1639804155.396711224]: imu plugin missing , defaults to 0.0
[ INFO] [1639804155.419041116]: Loading gazebo_ros_control plugin
[ INFO] [1639804155.422676439]: Starting gazebo_ros_control plugin in namespace:
[ INFO] [1639804155.423273531]: gazebo_ros_control plugin is waiting for model URDF in parameter [/robot_description] on the ROS param server.
Segmentation fault (core dumped)
[gazebo-2] process has died [pid 12686, exit code 139, cmd /home/apanrtx/catkin_ws/src/gazebo_ros_pkgs/gazebo_ros/scripts/gzserver -u -e ode /home/apanrtx/catkin_ws/src/panda_simulator/panda_gazebo/worlds/panda.world __name:=gazebo __log:=/home/apanrtx/.ros/log/a2a1954a-5fc0-11ec-8a29-04d4c45b62cf/gazebo-2.log].
log file: /home/apanrtx/.ros/log/a2a1954a-5fc0-11ec-8a29-04d4c45b62cf/gazebo-2*.log
[ERROR] [1639804156.394434, 0.000000]: SetModelConfiguration service failed. Exiting.
[robot_description-4] process has died [pid 12698, exit code 1, cmd /home/apanrtx/catkin_ws/src/gazebo_ros_pkgs/gazebo_ros/scripts/spawn_model -param robot_description -urdf -model panda -J panda::panda_joint1 0.000 -J panda::panda_joint2 -0.785 -J panda::panda_joint3 0.0 -J panda::panda_joint4 -2.356 -J panda::panda_joint5 0.0 -J panda::panda_joint6 1.57 -J panda::panda_joint7 0.785 __name:=robot_description __log:=/home/apanrtx/.ros/log/a2a1954a-5fc0-11ec-8a29-04d4c45b62cf/robot_description-4.log].
log file: /home/apanrtx/.ros/log/a2a1954a-5fc0-11ec-8a29-04d4c45b62cf/robot_description-4*.log

Trajectory replacing support

Hi,

regarding your Trajectory Action controller. I wanted to ask if it supports the replace of the trajectory on go without the need of stopping the execution. Replace the old trajectory by aligned new one.

If not, what it possibly needed to be done to make it possible.

It would help us a lot. Thank you for your time.

Process finished on startup and demo fail

Hi,

I'm coming back with a fresh install (Pop Os - ubuntu 20-04) with ros noetic. The build did go well but I'm unable to launch the demo.
In the first terminal (roslaunch panda_gazebo panda_world.launch) :

roslaunch panda_gazebo panda_world.launch            
... logging to /home/altair/.ros/log/0bbe3e08-0516-11ec-b610-fb6eaaf7b86e/roslaunch-pop-os-97470.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

xacro: in-order processing became default in ROS Melodic. You can drop the option.
started roslaunch server http://pop-os:42933/


PARAMETERS
 * /SIMULATOR_: True
 * /arm/gravity_tip_name: panda_hand
 * /arm/root_name: panda_link0
 * /arm/tip_name: panda_hand
 * /controllers_config/default_controller: panda_simulator/p...
 * /controllers_config/position_controller: panda_simulator/p...
 * /controllers_config/torque_controller: panda_simulator/e...
 * /controllers_config/velocity_controller: panda_simulator/v...
 * /franka_gripper/robot_ip: sim
 * /gazebo/enable_ros_network: True
 * /gripper_config/default_grasp_epsilon/inner: 0.005
 * /gripper_config/default_grasp_epsilon/outer: 0.005
 * /gripper_config/default_speed: 0.1
 * /gripper_config/joint_names: ['panda_finger_jo...
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/effort_joint_gravity_controller/type: panda_sim_control...
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/effort_joint_torque_controller/topic: /panda_simulator/...
 * /panda_simulator/effort_joint_torque_controller/type: panda_sim_control...
 * /panda_simulator/joint_state_controller/publish_rate: 100
 * /panda_simulator/joint_state_controller/type: joint_state_contr...
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/joint: panda_finger_joint1
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/d: 0.5
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/i: 50
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/p: 5000
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/joint: panda_finger_joint2
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/d: 0.5
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/i: 50
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/p: 5000
 * /panda_simulator/panda_gripper_controller/pub_topic: /franka_gripper/j...
 * /panda_simulator/panda_gripper_controller/type: panda_sim_control...
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/d: 25.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/d: 30.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/d: 30.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/d: 50.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/d: 8.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/d: 5.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/i: 1.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/d: 4.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/topic_joint_command: /panda_simulator/...
 * /panda_simulator/position_joint_position_controller/topic_set_speed_ratio: /panda_simulator/...
 * /panda_simulator/position_joint_position_controller/type: panda_sim_control...
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/d: 0.1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/p: 10
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/d: 0.1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/i: 1.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/p: 100
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/p: 0.05
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/d: 0.1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/i: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/p: 0.5
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/p: 1.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/p: 0.05
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/p: 0.05
 * /panda_simulator/velocity_joint_velocity_controller/topic: /panda_simulator/...
 * /panda_simulator/velocity_joint_velocity_controller/type: panda_sim_control...
 * /robot_config/arm_id: panda
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint1: 15.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint2: 7.5
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint3: 10.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint4: 12.5
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint5: 15.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint6: 20.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint7: 20.0
 * /robot_config/joint_config/joint_effort_limit/panda_joint1: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint2: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint3: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint4: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint5: 12
 * /robot_config/joint_config/joint_effort_limit/panda_joint6: 12
 * /robot_config/joint_config/joint_effort_limit/panda_joint7: 12
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint1: -2.8973
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint2: -1.7628
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint3: -2.8973
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint4: -3.0718
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint5: -2.8973
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint6: -0.0175
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint7: -2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint1: 2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint2: 1.7628
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint3: 2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint4: -0.0698
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint5: 2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint6: 3.7525
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint7: 2.8973
 * /robot_config/joint_config/joint_velocity_limit/panda_joint1: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint2: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint3: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint4: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint5: 2.61
 * /robot_config/joint_config/joint_velocity_limit/panda_joint6: 2.61
 * /robot_config/joint_config/joint_velocity_limit/panda_joint7: 2.61
 * /robot_config/joint_names: ['panda_joint1', ...
 * /robot_config/neutral_pose/panda_joint1: -0.01779206022777...
 * /robot_config/neutral_pose/panda_joint2: -0.7601235411041661
 * /robot_config/neutral_pose/panda_joint3: 0.019782607023391807
 * /robot_config/neutral_pose/panda_joint4: -2.342050140544315
 * /robot_config/neutral_pose/panda_joint5: 0.029840531355804868
 * /robot_config/neutral_pose/panda_joint6: 1.5411935298621688
 * /robot_config/neutral_pose/panda_joint7: 0.7534486589746342
 * /robot_description: <?xml version="1....
 * /rosdistro: noetic
 * /rosversion: 1.15.11
 * /use_sim_time: True

NODES
  /
    base_to_link0 (tf/static_transform_publisher)
    controller_spawner (controller_manager/controller_manager)
    controller_spawner_stopped (controller_manager/controller_manager)
    gazebo (gazebo_ros/gzserver)
    gazebo_gui (gazebo_ros/gzclient)
    gripper_action_server_emulator (panda_sim_custom_action_server/start_gripper_action_server.py)
    joint_trajectory_server_emulator (panda_sim_custom_action_server/start_joint_trajectory_server.py)
    panda_gripper_controller_spawner_stopped (controller_manager/controller_manager)
    robot_description (gazebo_ros/spawn_model)
    robot_state_publisher (robot_state_publisher/robot_state_publisher)
    startup_script (panda_gazebo/force_neutral_pose.py)
    topic_remap (topic_tools/relay)
    world_to_base (tf/static_transform_publisher)

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

setting /run_id to 0bbe3e08-0516-11ec-b610-fb6eaaf7b86e
process[rosout-1]: started with pid [97490]
started core service [/rosout]
process[gazebo-2]: started with pid [97497]
process[gazebo_gui-3]: started with pid [97502]
process[robot_description-4]: started with pid [97507]
process[base_to_link0-5]: started with pid [97508]
process[world_to_base-6]: started with pid [97509]
process[controller_spawner-7]: started with pid [97510]
process[controller_spawner_stopped-8]: started with pid [97515]
process[panda_gripper_controller_spawner_stopped-9]: started with pid [97521]
process[robot_state_publisher-10]: started with pid [97523]
process[topic_remap-11]: started with pid [97524]
process[joint_trajectory_server_emulator-12]: started with pid [97525]
process[gripper_action_server_emulator-13]: started with pid [97527]
process[startup_script-14]: started with pid [97535]
[ INFO] [1629835280.856458815]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1629835280.858460428]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1629835280.953158512]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1629835280.953965227]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting...
[ INFO] [1629835281.622778558, 0.003000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1629835281.912655345, 0.156000000]: ft_sensor plugin reporting wrench values to the frame [panda_link7]
[ INFO] [1629835281.914405870, 0.156000000]: Physics dynamic reconfigure ready.
[ INFO] [1629835281.914472574, 0.156000000]: imu plugin missing <gaussianNoise>, defaults to 0.0
[ INFO] [1629835281.941126326, 0.156000000]: Loading gazebo_ros_control plugin
[ INFO] [1629835281.943643050, 0.156000000]: Starting gazebo_ros_control plugin in namespace: 
[ INFO] [1629835281.944251375, 0.156000000]: gazebo_ros_control plugin is waiting for model URDF in parameter [/robot_description] on the ROS param server.
[ INFO] [1629835282.075440873, 0.156000000]: Loaded gazebo_ros_control.
[ INFO] [1629835282.090101636, 0.156000000]: Unable to find Acceleration values for joint panda_finger_joint1...
[ INFO] [1629835282.090298804, 0.156000000]: Unable to find Acceleration values for joint panda_finger_joint2...
[ INFO] [1629835282.251800122, 0.298000000]: Initializing JointArrayController(type:/panda_simulator/velocity_joint_velocity_controller) with 7 joints.
[ INFO] [1629835282.251943900, 0.298000000]: Loading sub-controller 'panda_joint1_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller
[ INFO] [1629835282.278034911, 0.324000000]: Loading sub-controller 'panda_joint2_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller
[ INFO] [1629835282.309383107, 0.354000000]: Loading sub-controller 'panda_joint3_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller
[ INFO] [1629835282.337578112, 0.382000000]: Loading sub-controller 'panda_joint4_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller
[ INFO] [1629835282.369774931, 0.414000000]: Loading sub-controller 'panda_joint5_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller
[ INFO] [1629835282.400065204, 0.444000000]: Loading sub-controller 'panda_joint6_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller
[ INFO] [1629835282.429930124, 0.474000000]: Loading sub-controller 'panda_joint7_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller
Loaded 'panda_simulator/velocity_joint_velocity_controller'
[ INFO] [1629835282.475253173, 0.519000000]: Initializing JointArrayController(type:/panda_simulator/position_joint_position_controller) with 7 joints.
[ INFO] [1629835282.475419133, 0.519000000]: Loading sub-controller 'panda_joint1_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller
[ INFO] [1629835282.507751645, 0.551000000]: Loading sub-controller 'panda_joint2_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller
[ INFO] [1629835282.541094300, 0.584000000]: Loading sub-controller 'panda_joint3_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller
[ INFO] [1629835282.573736069, 0.617000000]: Loading sub-controller 'panda_joint4_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller
[ INFO] [1629835282.603974224, 0.647000000]: Loading sub-controller 'panda_joint5_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller
[ INFO] [1629835282.636188296, 0.679000000]: Loading sub-controller 'panda_joint6_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller
[ INFO] [1629835282.663776890, 0.707000000]: Loading sub-controller 'panda_joint7_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller
Loaded 'panda_simulator/position_joint_position_controller'
[ INFO] [1629835282.713604421, 0.756000000]: Initializing PandaGripperController with 2 joints.
[ INFO] [1629835282.714270964, 0.757000000]: Loading sub-controller 'panda_finger_joint1_controller', Namespace: /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller
[ INFO] [1629835282.748731064, 0.791000000]: Loading sub-controller 'panda_finger_joint2_controller', Namespace: /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller
Loaded 'panda_simulator/panda_gripper_controller'
[ INFO] [1629835282.843782079, 0.886000000]: Initializing JointArrayController(type:/panda_simulator/effort_joint_gravity_controller) with 7 joints.
[ INFO] [1629835282.843899928, 0.886000000]: Loading sub-controller 'panda_joint1_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint1_controller
[ INFO] [1629835282.845626038, 0.887000000]: Loading sub-controller 'panda_joint2_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint2_controller
[ INFO] [1629835282.846686105, 0.889000000]: Loading sub-controller 'panda_joint3_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint3_controller
[ INFO] [1629835282.847546590, 0.889000000]: Loading sub-controller 'panda_joint4_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint4_controller
[ INFO] [1629835282.847906802, 0.890000000]: Loading sub-controller 'panda_joint5_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint5_controller
[ INFO] [1629835282.848160886, 0.890000000]: Loading sub-controller 'panda_joint6_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint6_controller
[ INFO] [1629835282.848654256, 0.890000000]: Loading sub-controller 'panda_joint7_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint7_controller
Loaded 'panda_simulator/effort_joint_gravity_controller'
Loaded 'panda_simulator/joint_state_controller'
Started ['panda_simulator/panda_gripper_controller'] successfully
[ INFO] [1629835282.868572464, 0.910000000]: Initializing JointArrayController(type:/panda_simulator/effort_joint_torque_controller) with 7 joints.
[ INFO] [1629835282.868631604, 0.911000000]: Loading sub-controller 'panda_joint1_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint1_controller
[ INFO] [1629835282.871160471, 0.913000000]: Loading sub-controller 'panda_joint2_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint2_controller
[ INFO] [1629835282.874370317, 0.916000000]: Loading sub-controller 'panda_joint3_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint3_controller
[ INFO] [1629835282.876245615, 0.918000000]: Loading sub-controller 'panda_joint4_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint4_controller
[ INFO] [1629835282.878967852, 0.921000000]: Loading sub-controller 'panda_joint5_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint5_controller
[ INFO] [1629835282.882363174, 0.924000000]: Loading sub-controller 'panda_joint6_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint6_controller
[ INFO] [1629835282.884500250, 0.927000000]: Loading sub-controller 'panda_joint7_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint7_controller
Loaded 'panda_simulator/effort_joint_torque_controller'
Started ['panda_simulator/position_joint_position_controller'] successfully
Started ['panda_simulator/joint_state_controller'] successfully
[panda_gripper_controller_spawner_stopped-9] process has finished cleanly
log file: /home/altair/.ros/log/0bbe3e08-0516-11ec-b610-fb6eaaf7b86e/panda_gripper_controller_spawner_stopped-9*.log
[ INFO] [1629835283.653160986, 1.692000000]: ArmControllerInterface: Controller panda_simulator/position_joint_position_controller started; Controllers panda_simulator/effort_joint_torque_controller, panda_simulator/velocity_joint_velocity_controller stopped.
[robot_description-4] process has finished cleanly
log file: /home/altair/.ros/log/0bbe3e08-0516-11ec-b610-fb6eaaf7b86e/robot_description-4*.log
[controller_spawner-7] process has finished cleanly
log file: /home/altair/.ros/log/0bbe3e08-0516-11ec-b610-fb6eaaf7b86e/controller_spawner-7*.log
[controller_spawner_stopped-8] process has finished cleanly
log file: /home/altair/.ros/log/0bbe3e08-0516-11ec-b610-fb6eaaf7b86e/controller_spawner_stopped-8*.log
[startup_script-14] process has finished cleanly
log file: /home/altair/.ros/log/0bbe3e08-0516-11ec-b610-fb6eaaf7b86e/startup_script-14*.log

and in the second terminal :

roslaunch panda_simulator_examples demo_moveit.launch
... logging to /home/altair/.ros/log/0bbe3e08-0516-11ec-b610-fb6eaaf7b86e/roslaunch-pop-os-101383.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.

started roslaunch server http://pop-os:34079/

SUMMARY
========

PARAMETERS
 * /panda_arm/kinematics_solver: kdl_kinematics_pl...
 * /panda_arm/kinematics_solver_search_resolution: 0.005
 * /panda_arm/kinematics_solver_timeout: 0.05
 * /robot_description_kinematics/panda_arm/kinematics_solver: kdl_kinematics_pl...
 * /robot_description_kinematics/panda_arm/kinematics_solver_search_resolution: 0.005
 * /robot_description_kinematics/panda_arm/kinematics_solver_timeout: 0.05
 * /robot_description_planning/joint_limits/panda_finger_joint1/has_acceleration_limits: False
 * /robot_description_planning/joint_limits/panda_finger_joint1/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_finger_joint1/max_acceleration: 0
 * /robot_description_planning/joint_limits/panda_finger_joint1/max_velocity: 0.1
 * /robot_description_planning/joint_limits/panda_finger_joint2/has_acceleration_limits: False
 * /robot_description_planning/joint_limits/panda_finger_joint2/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_finger_joint2/max_acceleration: 0
 * /robot_description_planning/joint_limits/panda_finger_joint2/max_velocity: 0.1
 * /robot_description_planning/joint_limits/panda_joint1/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint1/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint1/max_acceleration: 3.75
 * /robot_description_planning/joint_limits/panda_joint1/max_velocity: 2.175
 * /robot_description_planning/joint_limits/panda_joint2/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint2/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint2/max_acceleration: 1.875
 * /robot_description_planning/joint_limits/panda_joint2/max_velocity: 2.175
 * /robot_description_planning/joint_limits/panda_joint3/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint3/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint3/max_acceleration: 2.5
 * /robot_description_planning/joint_limits/panda_joint3/max_velocity: 2.175
 * /robot_description_planning/joint_limits/panda_joint4/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint4/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint4/max_acceleration: 3.125
 * /robot_description_planning/joint_limits/panda_joint4/max_velocity: 2.175
 * /robot_description_planning/joint_limits/panda_joint5/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint5/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint5/max_acceleration: 3.75
 * /robot_description_planning/joint_limits/panda_joint5/max_velocity: 2.61
 * /robot_description_planning/joint_limits/panda_joint6/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint6/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint6/max_acceleration: 5
 * /robot_description_planning/joint_limits/panda_joint6/max_velocity: 2.61
 * /robot_description_planning/joint_limits/panda_joint7/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint7/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint7/max_acceleration: 5
 * /robot_description_planning/joint_limits/panda_joint7/max_velocity: 2.61
 * /robot_description_semantic: <?xml version="1....
 * /rosdistro: noetic
 * /rosversion: 1.15.11

NODES
  /
    demo_boxes_scene_loader (franka_moveit/test_scene_interface.py)
    rviz_pop_os_101383_8150143687552990353 (rviz/rviz)

ROS_MASTER_URI=http://localhost:11311

process[rviz_pop_os_101383_8150143687552990353-1]: started with pid [101561]
process[demo_boxes_scene_loader-2]: started with pid [101563]
[ INFO] [1629835322.120228426]: rviz version 1.14.8
[ INFO] [1629835322.120265546]: compiled against Qt version 5.12.8
[ INFO] [1629835322.120274703]: compiled against OGRE version 1.9.0 (Ghadamon)
[ INFO] [1629835322.132806126]: Forcing OpenGl version 0.
[ INFO] [1629835322.695280690, 40.083000000]: Stereo is NOT SUPPORTED
[ INFO] [1629835322.695440728, 40.083000000]: OpenGL device: NVIDIA GeForce RTX 3060 Laptop GPU/PCIe/SSE2
[ INFO] [1629835322.695492104, 40.083000000]: OpenGl version: 4.6 (GLSL 4.6).
============ Starting test ...
[ INFO] [1629835326.043801971, 43.381000000]: Loading robot model 'panda'...
[ INFO] [1629835326.043862784, 43.381000000]: Loading robot model 'panda'...
[ WARN] [1629835326.043889975, 43.381000000]: Skipping virtual joint 'virtual_joint' because its child frame 'panda_link0' does not match the URDF frame 'world'
[ INFO] [1629835326.043915623, 43.381000000]: No root/virtual joint specified in SRDF. Assuming fixed joint
[ WARN] [1629835326.043940109, 43.381000000]: Skipping virtual joint 'virtual_joint' because its child frame 'panda_link0' does not match the URDF frame 'world'
[ INFO] [1629835326.043971437, 43.381000000]: No root/virtual joint specified in SRDF. Assuming fixed joint
[ INFO] [1629835326.163202442, 43.498000000]: Starting planning scene monitor
[ INFO] [1629835326.168657447, 43.504000000]: Listening to '/planning_scene'
[ INFO] [1629835326.531438524, 43.865000000]: Starting planning scene monitor
[ INFO] [1629835326.531972379, 43.866000000]: waitForService: Service [/get_planning_scene] has not been advertised, waiting...
[ INFO] [1629835326.533571499, 43.868000000]: Listening to '/move_group/monitored_planning_scene'
[ INFO] [1629835326.535292546, 43.869000000]: waitForService: Service [/get_planning_scene] has not been advertised, waiting...
============ Press `Enter` to begin the tutorial by setting up the scene_interface (press ctrl-d to exit) ...[ INFO] [1629835331.539019239, 48.810000000]: Failed to call service get_planning_scene, have you launched move_group or called psm.providePlanningSceneService()?
[ INFO] [1629835331.542013788, 48.813000000]: Failed to call service get_planning_scene, have you launched move_group or called psm.providePlanningSceneService()?
[ INFO] [1629835331.542183665, 48.813000000]: Constructing new MoveGroup connection for group 'panda_arm' in namespace ''
[ERROR] [1629835361.552563965, 78.290000000]: Unable to connect to move_group action server 'move_group' within allotted time (30s)
[ERROR] [1629835361.557176535, 78.295000000]: Could not find parameter for database plugin name

I think the controllers are not properly starting but not sure at all...

Anway, thanks a lot for your work. That would save the end of my PhD if it works !

Python f strings exceptions

I followed the "Installation" guide (kinetic, resolved dependencies then used the build script) with no error. When trying to launch the simulator as per the "Usage" section, I face the following exceptions. I read the "Known Issues" and the already resolved issues with no mention of this problem. What do you think it could be? AFAIK f strings are from python 3 and not 2, but kinetic runs on python 2.

Traceback (most recent call last):
  File "/home/ap/catkin_ws/src/panda_simulator/panda_sim_custom_action_server/scripts/start_gripper_action_server.py", line 33, in <module>
    from panda_sim_custom_action_server import GripperActionServer
  File "/home/ap/catkin_ws/devel/lib/python2.7/dist-packages/panda_sim_custom_action_server/__init__.py", line 34, in <module>
    exec(__fh.read())
  File "<string>", line 18, in <module>
  File "/home/ap/catkin_ws/src/panda_simulator/panda_sim_custom_action_server/src/panda_sim_custom_action_server/joint_trajectory_action_server.py", line 60, in <module>
    import franka_interface
  File "/home/ap/catkin_ws/src/franka_ros_interface/franka_interface/src/franka_interface/__init__.py", line 18, in <module>
    from .arm import ArmInterface
  File "/home/ap/catkin_ws/src/franka_ros_interface/franka_interface/src/franka_interface/arm.py", line 37, in <module>
    import quaternion
  File "/home/ap/.local/lib/python2.7/site-packages/quaternion/__init__.py", line 29, in <module>
    from .quaternion_time_series import (
  File "/home/ap/.local/lib/python2.7/site-packages/quaternion/quaternion_time_series.py", line 48
    raise ValueError(f"Requested axis {axis} is outside the input array's shape {q.shape}")
                                                                                         ^
SyntaxError: invalid syntax
Traceback (most recent call last):
  File "/home/ap/catkin_ws/src/panda_simulator/panda_sim_custom_action_server/scripts/start_joint_trajectory_server.py", line 40, in <module>
    from panda_sim_custom_action_server import (
  File "/home/ap/catkin_ws/devel/lib/python2.7/dist-packages/panda_sim_custom_action_server/__init__.py", line 34, in <module>
    exec(__fh.read())
  File "<string>", line 18, in <module>
  File "/home/ap/catkin_ws/src/panda_simulator/panda_sim_custom_action_server/src/panda_sim_custom_action_server/joint_trajectory_action_server.py", line 60, in <module>
    import franka_interface
  File "/home/ap/catkin_ws/src/franka_ros_interface/franka_interface/src/franka_interface/__init__.py", line 18, in <module>
    from .arm import ArmInterface
  File "/home/ap/catkin_ws/src/franka_ros_interface/franka_interface/src/franka_interface/arm.py", line 37, in <module>
    import quaternion
  File "/home/ap/.local/lib/python2.7/site-packages/quaternion/__init__.py", line 29, in <module>
    from .quaternion_time_series import (
  File "/home/ap/.local/lib/python2.7/site-packages/quaternion/quaternion_time_series.py", line 48
    raise ValueError(f"Requested axis {axis} is outside the input array's shape {q.shape}")
                                                                                         ^
SyntaxError: invalid syntax

Can't pick up the objects in Gazebo

I want to simulate basic pick and place using Panda arm in Gazebo. I can move the arm very well in Gazebo using Rviz but I don't have absolute control over gripper in Rviz except open and close.

However I've spawned the arm in my world and I'm able to execute Rviz motion plan in Gazebo but the gripper can't grip the object. The attached video demonstrates the problem well.

Please guide how to fix this problem and if I want to control the gripper manually using ROS and embed it in my motion plan, how can that be done? Would really appreciate the help :)

Screencast.from.23-12-20.20.15.38.mp4

Does this project have position control in Cartesian space?

Moveit motion planning will automatically detect collisions, but this is not what I want, so I don't want to use ROS motion planning. Does this project support motion planning in Cartesian space? I don't find a related package or library about Cartesian space.

how to transfer the controller from sim to real.

Hi, thanks for your work. I have a question about how to transfer the controller from sim to real.
Can I directly use the controller designed in "panda simulator" to drive Franka robot in reality? For example, I change the script "task_space_control_with_fri.py" as an impedance controller, and it works in the simulator. Can I directly copy it and paste in "franka_ros_interface/franka_ros_controllers/scripts/test" , and run it as "test_controller.py"?

Gravity

Hi !

I run the simulator on noetic and I had trouble using some gazebo model objects I was previously using. it seems like there is no gravity in the world launched. That caused my objects to be affected and float around when I interact with them. I tried to set the gravity within the object sdf but without effect (the world seemed to override this). I activated the gravity in the panda.world and I can interact with my objects like before without (for now) bad consequences for the robot. I precise that I use the moveit interface.
Was there a specific reason to disable the gravity ?

Action client not connected: position_joint_trajectory_controller/follow_joint_trajectory

timing out on the joint trajectory controller? see output below:

$ roslaunch panda_gazebo panda_world.launch 
... logging to /home/local/.ros/log/97cc4ace-9515-11ea-beed-3c6aa7cb24ab/roslaunch-PandaExpress-3151.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

xacro: in-order processing became default in ROS Melodic. You can drop the option.
started roslaunch server http://PandaExpress:45809/

SUMMARY
========

PARAMETERS
 * /SIMULATOR_: True
 * /arm/gravity_tip_name: panda_hand
 * /arm/root_name: panda_link0
 * /arm/tip_name: panda_hand
 * /controllers_config/default_controller: panda_simulator/p...
 * /controllers_config/position_controller: panda_simulator/p...
 * /controllers_config/torque_controller: panda_simulator/e...
 * /controllers_config/velocity_controller: panda_simulator/v...
 * /franka_gripper/robot_ip: sim
 * /gazebo/enable_ros_network: True
 * /gripper_config/default_grasp_epsilon/inner: 0.005
 * /gripper_config/default_grasp_epsilon/outer: 0.005
 * /gripper_config/default_speed: 0.1
 * /gripper_config/joint_names: ['panda_finger_jo...
 * /move_group/allow_trajectory_execution: True
 * /move_group/controller_list: [{'default': True...
 * /move_group/hand/planner_configs: ['SBLkConfigDefau...
 * /move_group/jiggle_fraction: 0.05
 * /move_group/max_range: 5.0
 * /move_group/max_safe_path_cost: 1
 * /move_group/moveit_controller_manager: moveit_simple_con...
 * /move_group/moveit_manage_controllers: True
 * /move_group/octomap_frame: camera_rgb_optica...
 * /move_group/octomap_resolution: 0.05
 * /move_group/panda_arm/planner_configs: ['SBLkConfigDefau...
 * /move_group/panda_arm_hand/planner_configs: ['SBLkConfigDefau...
 * /move_group/planner_configs/BFMTkConfigDefault/balanced: 0
 * /move_group/planner_configs/BFMTkConfigDefault/cache_cc: 1
 * /move_group/planner_configs/BFMTkConfigDefault/extended_fmt: 1
 * /move_group/planner_configs/BFMTkConfigDefault/heuristics: 1
 * /move_group/planner_configs/BFMTkConfigDefault/nearest_k: 1
 * /move_group/planner_configs/BFMTkConfigDefault/num_samples: 1000
 * /move_group/planner_configs/BFMTkConfigDefault/optimality: 1
 * /move_group/planner_configs/BFMTkConfigDefault/radius_multiplier: 1.0
 * /move_group/planner_configs/BFMTkConfigDefault/type: geometric::BFMT
 * /move_group/planner_configs/BKPIECEkConfigDefault/border_fraction: 0.9
 * /move_group/planner_configs/BKPIECEkConfigDefault/failed_expansion_score_factor: 0.5
 * /move_group/planner_configs/BKPIECEkConfigDefault/min_valid_path_fraction: 0.5
 * /move_group/planner_configs/BKPIECEkConfigDefault/range: 0.0
 * /move_group/planner_configs/BKPIECEkConfigDefault/type: geometric::BKPIECE
 * /move_group/planner_configs/BiESTkConfigDefault/range: 0.0
 * /move_group/planner_configs/BiESTkConfigDefault/type: geometric::BiEST
 * /move_group/planner_configs/BiTRRTkConfigDefault/cost_threshold: 1e300
 * /move_group/planner_configs/BiTRRTkConfigDefault/frountier_node_ratio: 0.1
 * /move_group/planner_configs/BiTRRTkConfigDefault/frountier_threshold: 0.0
 * /move_group/planner_configs/BiTRRTkConfigDefault/init_temperature: 100
 * /move_group/planner_configs/BiTRRTkConfigDefault/range: 0.0
 * /move_group/planner_configs/BiTRRTkConfigDefault/temp_change_factor: 0.1
 * /move_group/planner_configs/BiTRRTkConfigDefault/type: geometric::BiTRRT
 * /move_group/planner_configs/ESTkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/ESTkConfigDefault/range: 0.0
 * /move_group/planner_configs/ESTkConfigDefault/type: geometric::EST
 * /move_group/planner_configs/FMTkConfigDefault/cache_cc: 1
 * /move_group/planner_configs/FMTkConfigDefault/extended_fmt: 1
 * /move_group/planner_configs/FMTkConfigDefault/heuristics: 0
 * /move_group/planner_configs/FMTkConfigDefault/nearest_k: 1
 * /move_group/planner_configs/FMTkConfigDefault/num_samples: 1000
 * /move_group/planner_configs/FMTkConfigDefault/radius_multiplier: 1.1
 * /move_group/planner_configs/FMTkConfigDefault/type: geometric::FMT
 * /move_group/planner_configs/KPIECEkConfigDefault/border_fraction: 0.9
 * /move_group/planner_configs/KPIECEkConfigDefault/failed_expansion_score_factor: 0.5
 * /move_group/planner_configs/KPIECEkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/KPIECEkConfigDefault/min_valid_path_fraction: 0.5
 * /move_group/planner_configs/KPIECEkConfigDefault/range: 0.0
 * /move_group/planner_configs/KPIECEkConfigDefault/type: geometric::KPIECE
 * /move_group/planner_configs/LBKPIECEkConfigDefault/border_fraction: 0.9
 * /move_group/planner_configs/LBKPIECEkConfigDefault/min_valid_path_fraction: 0.5
 * /move_group/planner_configs/LBKPIECEkConfigDefault/range: 0.0
 * /move_group/planner_configs/LBKPIECEkConfigDefault/type: geometric::LBKPIECE
 * /move_group/planner_configs/LBTRRTkConfigDefault/epsilon: 0.4
 * /move_group/planner_configs/LBTRRTkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/LBTRRTkConfigDefault/range: 0.0
 * /move_group/planner_configs/LBTRRTkConfigDefault/type: geometric::LBTRRT
 * /move_group/planner_configs/LazyPRMkConfigDefault/range: 0.0
 * /move_group/planner_configs/LazyPRMkConfigDefault/type: geometric::LazyPRM
 * /move_group/planner_configs/LazyPRMstarkConfigDefault/type: geometric::LazyPR...
 * /move_group/planner_configs/PDSTkConfigDefault/type: geometric::PDST
 * /move_group/planner_configs/PRMkConfigDefault/max_nearest_neighbors: 10
 * /move_group/planner_configs/PRMkConfigDefault/type: geometric::PRM
 * /move_group/planner_configs/PRMstarkConfigDefault/type: geometric::PRMstar
 * /move_group/planner_configs/ProjESTkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/ProjESTkConfigDefault/range: 0.0
 * /move_group/planner_configs/ProjESTkConfigDefault/type: geometric::ProjEST
 * /move_group/planner_configs/RRTConnectkConfigDefault/range: 0.0
 * /move_group/planner_configs/RRTConnectkConfigDefault/type: geometric::RRTCon...
 * /move_group/planner_configs/RRTkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/RRTkConfigDefault/range: 0.0
 * /move_group/planner_configs/RRTkConfigDefault/type: geometric::RRT
 * /move_group/planner_configs/RRTstarkConfigDefault/delay_collision_checking: 1
 * /move_group/planner_configs/RRTstarkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/RRTstarkConfigDefault/range: 0.0
 * /move_group/planner_configs/RRTstarkConfigDefault/type: geometric::RRTstar
 * /move_group/planner_configs/SBLkConfigDefault/range: 0.0
 * /move_group/planner_configs/SBLkConfigDefault/type: geometric::SBL
 * /move_group/planner_configs/SPARSkConfigDefault/dense_delta_fraction: 0.001
 * /move_group/planner_configs/SPARSkConfigDefault/max_failures: 1000
 * /move_group/planner_configs/SPARSkConfigDefault/sparse_delta_fraction: 0.25
 * /move_group/planner_configs/SPARSkConfigDefault/stretch_factor: 3.0
 * /move_group/planner_configs/SPARSkConfigDefault/type: geometric::SPARS
 * /move_group/planner_configs/SPARStwokConfigDefault/dense_delta_fraction: 0.001
 * /move_group/planner_configs/SPARStwokConfigDefault/max_failures: 5000
 * /move_group/planner_configs/SPARStwokConfigDefault/sparse_delta_fraction: 0.25
 * /move_group/planner_configs/SPARStwokConfigDefault/stretch_factor: 3.0
 * /move_group/planner_configs/SPARStwokConfigDefault/type: geometric::SPARStwo
 * /move_group/planner_configs/STRIDEkConfigDefault/degree: 16
 * /move_group/planner_configs/STRIDEkConfigDefault/estimated_dimension: 0.0
 * /move_group/planner_configs/STRIDEkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/STRIDEkConfigDefault/max_degree: 18
 * /move_group/planner_configs/STRIDEkConfigDefault/max_pts_per_leaf: 6
 * /move_group/planner_configs/STRIDEkConfigDefault/min_degree: 12
 * /move_group/planner_configs/STRIDEkConfigDefault/min_valid_path_fraction: 0.2
 * /move_group/planner_configs/STRIDEkConfigDefault/range: 0.0
 * /move_group/planner_configs/STRIDEkConfigDefault/type: geometric::STRIDE
 * /move_group/planner_configs/STRIDEkConfigDefault/use_projected_distance: 0
 * /move_group/planner_configs/TRRTkConfigDefault/frountierNodeRatio: 0.1
 * /move_group/planner_configs/TRRTkConfigDefault/frountier_threshold: 0.0
 * /move_group/planner_configs/TRRTkConfigDefault/goal_bias: 0.05
 * /move_group/planner_configs/TRRTkConfigDefault/init_temperature: 10e-6
 * /move_group/planner_configs/TRRTkConfigDefault/k_constant: 0.0
 * /move_group/planner_configs/TRRTkConfigDefault/max_states_failed: 10
 * /move_group/planner_configs/TRRTkConfigDefault/min_temperature: 10e-10
 * /move_group/planner_configs/TRRTkConfigDefault/range: 0.0
 * /move_group/planner_configs/TRRTkConfigDefault/temp_change_factor: 2.0
 * /move_group/planner_configs/TRRTkConfigDefault/type: geometric::TRRT
 * /move_group/planner_configs/TrajOptDefault/type: geometric::TrajOpt
 * /move_group/planning_plugin: ompl_interface/OM...
 * /move_group/planning_scene_monitor/publish_geometry_updates: True
 * /move_group/planning_scene_monitor/publish_planning_scene: True
 * /move_group/planning_scene_monitor/publish_state_updates: True
 * /move_group/planning_scene_monitor/publish_transforms_updates: True
 * /move_group/request_adapters: default_planner_r...
 * /move_group/sensors: [{'point_subsampl...
 * /move_group/start_state_max_bounds_error: 0.1
 * /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
 * /panda_simulator/effort_joint_gravity_controller/command_topic: /panda_simulator/...
 * /panda_simulator/effort_joint_gravity_controller/disable_timeout: 0.2
 * /panda_simulator/effort_joint_gravity_controller/disable_topic: /panda_simulator/...
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/effort_joint_gravity_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/effort_joint_gravity_controller/type: panda_sim_control...
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/effort_joint_torque_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/effort_joint_torque_controller/topic: /panda_simulator/...
 * /panda_simulator/effort_joint_torque_controller/type: panda_sim_control...
 * /panda_simulator/joint_state_controller/publish_rate: 100
 * /panda_simulator/joint_state_controller/type: joint_state_contr...
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/joint: panda_finger_joint1
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/d: 0.5
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/i: 50
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller/pid/p: 5000
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/joint: panda_finger_joint2
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/d: 0.5
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/i: 50
 * /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller/pid/p: 5000
 * /panda_simulator/panda_gripper_controller/pub_topic: /franka_gripper/j...
 * /panda_simulator/panda_gripper_controller/type: panda_sim_control...
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/d: 25.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/d: 30.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/d: 30.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/d: 50.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/d: 8.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/d: 5.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/i: 1.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/d: 4.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/i: 10.0
 * /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller/pid/p: 3000
 * /panda_simulator/position_joint_position_controller/topic_joint_command: /panda_simulator/...
 * /panda_simulator/position_joint_position_controller/topic_set_speed_ratio: /panda_simulator/...
 * /panda_simulator/position_joint_position_controller/type: panda_sim_control...
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/joint: panda_joint1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/d: 0.1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller/pid/p: 10
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/joint: panda_joint2
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/d: 0.1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/i: 1.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller/pid/p: 100
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/joint: panda_joint3
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller/pid/p: 0.05
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/joint: panda_joint4
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/d: 0.1
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/i: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller/pid/p: 0.5
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/joint: panda_joint5
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller/pid/p: 1.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/joint: panda_joint6
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller/pid/p: 0.05
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/joint: panda_joint7
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/d: 0.01
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/i: 0.0
 * /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller/pid/p: 0.05
 * /panda_simulator/velocity_joint_velocity_controller/topic: /panda_simulator/...
 * /panda_simulator/velocity_joint_velocity_controller/type: panda_sim_control...
 * /robot_config/arm_id: panda
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint1: 15.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint2: 7.5
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint3: 10.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint4: 12.5
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint5: 15.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint6: 20.0
 * /robot_config/joint_config/joint_acceleration_limit/panda_joint7: 20.0
 * /robot_config/joint_config/joint_effort_limit/panda_joint1: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint2: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint3: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint4: 87
 * /robot_config/joint_config/joint_effort_limit/panda_joint5: 12
 * /robot_config/joint_config/joint_effort_limit/panda_joint6: 12
 * /robot_config/joint_config/joint_effort_limit/panda_joint7: 12
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint1: -2.8973
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint2: -1.7628
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint3: -2.8973
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint4: -3.0718
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint5: -2.8973
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint6: -0.0175
 * /robot_config/joint_config/joint_position_limit/lower/panda_joint7: -2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint1: 2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint2: 1.7628
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint3: 2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint4: -0.0698
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint5: 2.8973
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint6: 3.7525
 * /robot_config/joint_config/joint_position_limit/upper/panda_joint7: 2.8973
 * /robot_config/joint_config/joint_velocity_limit/panda_joint1: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint2: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint3: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint4: 2.175
 * /robot_config/joint_config/joint_velocity_limit/panda_joint5: 2.61
 * /robot_config/joint_config/joint_velocity_limit/panda_joint6: 2.61
 * /robot_config/joint_config/joint_velocity_limit/panda_joint7: 2.61
 * /robot_config/joint_names: ['panda_joint1', ...
 * /robot_config/neutral_pose/panda_joint1: -0.0177920602278
 * /robot_config/neutral_pose/panda_joint2: -0.760123541104
 * /robot_config/neutral_pose/panda_joint3: 0.0197826070234
 * /robot_config/neutral_pose/panda_joint4: -2.34205014054
 * /robot_config/neutral_pose/panda_joint5: 0.0298405313558
 * /robot_config/neutral_pose/panda_joint6: 1.54119352986
 * /robot_config/neutral_pose/panda_joint7: 0.753448658975
 * /robot_description: <?xml version="1....
 * /robot_description_kinematics/panda_arm/kinematics_solver: kdl_kinematics_pl...
 * /robot_description_kinematics/panda_arm/kinematics_solver_search_resolution: 0.005
 * /robot_description_kinematics/panda_arm/kinematics_solver_timeout: 0.05
 * /robot_description_planning/joint_limits/panda_finger_joint1/has_acceleration_limits: False
 * /robot_description_planning/joint_limits/panda_finger_joint1/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_finger_joint1/max_acceleration: 0
 * /robot_description_planning/joint_limits/panda_finger_joint1/max_velocity: 0.1
 * /robot_description_planning/joint_limits/panda_finger_joint2/has_acceleration_limits: False
 * /robot_description_planning/joint_limits/panda_finger_joint2/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_finger_joint2/max_acceleration: 0
 * /robot_description_planning/joint_limits/panda_finger_joint2/max_velocity: 0.1
 * /robot_description_planning/joint_limits/panda_joint1/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint1/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint1/max_acceleration: 3.75
 * /robot_description_planning/joint_limits/panda_joint1/max_velocity: 2.175
 * /robot_description_planning/joint_limits/panda_joint2/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint2/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint2/max_acceleration: 1.875
 * /robot_description_planning/joint_limits/panda_joint2/max_velocity: 2.175
 * /robot_description_planning/joint_limits/panda_joint3/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint3/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint3/max_acceleration: 2.5
 * /robot_description_planning/joint_limits/panda_joint3/max_velocity: 2.175
 * /robot_description_planning/joint_limits/panda_joint4/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint4/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint4/max_acceleration: 3.125
 * /robot_description_planning/joint_limits/panda_joint4/max_velocity: 2.175
 * /robot_description_planning/joint_limits/panda_joint5/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint5/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint5/max_acceleration: 3.75
 * /robot_description_planning/joint_limits/panda_joint5/max_velocity: 2.61
 * /robot_description_planning/joint_limits/panda_joint6/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint6/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint6/max_acceleration: 5
 * /robot_description_planning/joint_limits/panda_joint6/max_velocity: 2.61
 * /robot_description_planning/joint_limits/panda_joint7/has_acceleration_limits: True
 * /robot_description_planning/joint_limits/panda_joint7/has_velocity_limits: True
 * /robot_description_planning/joint_limits/panda_joint7/max_acceleration: 5
 * /robot_description_planning/joint_limits/panda_joint7/max_velocity: 2.61
 * /robot_description_semantic: <?xml version="1....
 * /rosdistro: melodic
 * /rosversion: 1.14.3
 * /use_sim_time: True

NODES
  /
    base_to_link0 (tf/static_transform_publisher)
    controller_spawner (controller_manager/controller_manager)
    controller_spawner_stopped (controller_manager/controller_manager)
    gazebo (gazebo_ros/gzserver)
    gazebo_gui (gazebo_ros/gzclient)
    gripper_action_server_emulator (panda_sim_custom_action_server/start_gripper_action_server.py)
    joint_trajectory_server_emulator (panda_sim_custom_action_server/start_joint_trajectory_server.py)
    move_group (moveit_ros_move_group/move_group)
    panda_gripper_controller_spawner_stopped (controller_manager/controller_manager)
    robot_description (gazebo_ros/spawn_model)
    robot_state_publisher (robot_state_publisher/robot_state_publisher)
    topic_remap (topic_tools/relay)

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

setting /run_id to 97cc4ace-9515-11ea-beed-3c6aa7cb24ab
process[rosout-1]: started with pid [3243]
started core service [/rosout]
process[gazebo-2]: started with pid [3250]
process[gazebo_gui-3]: started with pid [3255]
process[robot_description-4]: started with pid [3260]
process[base_to_link0-5]: started with pid [3261]
process[controller_spawner-6]: started with pid [3267]
process[controller_spawner_stopped-7]: started with pid [3269]
process[panda_gripper_controller_spawner_stopped-8]: started with pid [3270]
process[robot_state_publisher-9]: started with pid [3271]
process[topic_remap-10]: started with pid [3276]
process[joint_trajectory_server_emulator-11]: started with pid [3278]
process[gripper_action_server_emulator-12]: started with pid [3291]
process[move_group-13]: started with pid [3308]
[ INFO] [1589373057.835693149]: Loading robot model 'panda'...
[ WARN] [1589373057.836225552]: Skipping virtual joint 'virtual_joint' because its child frame 'panda_link0' does not match the URDF frame 'world'
[ INFO] [1589373057.836257130]: No root/virtual joint specified in SRDF. Assuming fixed joint
[ INFO] [1589373057.916479979]: Publishing maintained planning scene on 'monitored_planning_scene'
[ INFO] [1589373057.918309252]: MoveGroup debug mode is ON
Starting planning scene monitors...
[ INFO] [1589373057.918588453]: Starting planning scene monitor
[ INFO] [1589373057.920086982]: Listening to '/planning_scene'
[ INFO] [1589373057.920164291]: Starting world geometry update monitor for collision objects, attached objects, octomap updates.
[ INFO] [1589373057.921831800]: Listening to '/collision_object'
[ INFO] [1589373057.923409862]: Listening to '/planning_scene_world' for planning scene world geometry
[ INFO] [1589373057.953119555]: Listening to '/camera/depth_registered/points' using message filter with target frame 'world '
[ INFO] [1589373057.956600516]: Listening to '/attached_collision_object' for attached collision objects
Planning scene monitors started.
[ INFO] [1589373058.016202738]: Using planning interface 'OMPL'
[ INFO] [1589373058.019455125]: Param 'default_workspace_bounds' was not set. Using default value: 10
[ INFO] [1589373058.019776815]: Param 'start_state_max_bounds_error' was set to 0.1
[ INFO] [1589373058.020042527]: Param 'start_state_max_dt' was not set. Using default value: 0.5
[ INFO] [1589373058.020371616]: Param 'start_state_max_dt' was not set. Using default value: 0.5
[ INFO] [1589373058.020638865]: Param 'jiggle_fraction' was set to 0.05
[ INFO] [1589373058.020888400]: Param 'max_sampling_attempts' was not set. Using default value: 100
[ INFO] [1589373058.020983532]: Using planning request adapter 'Fix Workspace Bounds'
[ INFO] [1589373058.021106182]: Using planning request adapter 'Fix Start State Bounds'
[ INFO] [1589373058.021156041]: Using planning request adapter 'Fix Start State In Collision'
[ INFO] [1589373058.021208457]: Using planning request adapter 'Fix Start State Path Constraints'
[ INFO] [1589373058.021265144]: Using planning request adapter 'Resolve constraint frames to robot links'
[ INFO] [1589373058.021306946]: Using planning request adapter 'Add Time Parameterization'
/home/local/.local/lib/python2.7/site-packages/quaternion/numba_wrapper.py:21: UserWarning: 

!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
Could not import from numba, which means that some
parts of this code may run MUCH more slowly.  You
may wish to install numba.
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

  warnings.warn(warning_text)
[ INFO] [1589373058.375042809]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1589373058.376349786]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1589373058.377905593]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1589373058.378806980]: waitForService: Service [/gazebo_gui/set_physics_properties] has not been advertised, waiting...
/home/local/.local/lib/python2.7/site-packages/quaternion/numba_wrapper.py:21: UserWarning: 

!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!
Could not import from numba, which means that some
parts of this code may run MUCH more slowly.  You
may wish to install numba.
!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!

  warnings.warn(warning_text)
[ INFO] [1589373059.456889456, 0.030000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1589373059.689381188, 0.163000000]: Physics dynamic reconfigure ready.
[Err] [REST.cc:205] Error in REST request

libcurl: (51) SSL: no alternative certificate subject name matches target host name 'api.ignitionfuel.org'
[ INFO] [1589373059.714598464, 0.163000000]: Loading gazebo_ros_control plugin
[ INFO] [1589373059.716456408, 0.163000000]: Starting gazebo_ros_control plugin in namespace: 
[ INFO] [1589373059.716737617, 0.163000000]: gazebo_ros_control plugin is waiting for model URDF in parameter [/robot_description] on the ROS param server.
[ INFO] [1589373059.838942084, 0.163000000]: Loaded gazebo_ros_control.
[ INFO] [1589373059.845616394, 0.163000000]: Unable to find Acceleration values for joint panda_finger_joint1...
[ INFO] [1589373059.845651205, 0.163000000]: Unable to find Acceleration values for joint panda_finger_joint2...
[ INFO] [1589373059.859726789, 0.174000000]: Initializing PandaGripperController with 2 joints.
[ INFO] [1589373059.859871125, 0.174000000]: Loading sub-controller 'panda_finger_joint1_controller', Namespace: /panda_simulator/panda_gripper_controller/joints/panda_finger_joint1_controller
[ INFO] [1589373059.879632307, 0.193000000]: Loading sub-controller 'panda_finger_joint2_controller', Namespace: /panda_simulator/panda_gripper_controller/joints/panda_finger_joint2_controller
Loaded 'panda_simulator/panda_gripper_controller'
Started ['panda_simulator/panda_gripper_controller'] successfully
[ INFO] [1589373059.972005265, 0.285000000]: Initializing JointArrayController(type:/panda_simulator/velocity_joint_velocity_controller) with 7 joints.
[ INFO] [1589373059.972070195, 0.285000000]: Loading sub-controller 'panda_joint1_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint1_controller
[ INFO] [1589373059.984995640, 0.298000000]: Loading sub-controller 'panda_joint2_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint2_controller
[ INFO] [1589373059.997939286, 0.311000000]: Loading sub-controller 'panda_joint3_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint3_controller
[ INFO] [1589373060.009299215, 0.323000000]: Loading sub-controller 'panda_joint4_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint4_controller
[ INFO] [1589373060.020799963, 0.334000000]: Loading sub-controller 'panda_joint5_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint5_controller
[ INFO] [1589373060.043275684, 0.357000000]: Loading sub-controller 'panda_joint6_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint6_controller
[ INFO] [1589373060.060730804, 0.374000000]: Loading sub-controller 'panda_joint7_controller', Namespace: /panda_simulator/velocity_joint_velocity_controller/joints/panda_joint7_controller
Loaded 'panda_simulator/velocity_joint_velocity_controller'
[ INFO] [1589373060.109434536, 0.423000000]: Initializing JointArrayController(type:/panda_simulator/effort_joint_torque_controller) with 7 joints.
[ INFO] [1589373060.109472776, 0.423000000]: Loading sub-controller 'panda_joint1_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint1_controller
[ INFO] [1589373060.111231189, 0.425000000]: Loading sub-controller 'panda_joint2_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint2_controller
[ INFO] [1589373060.113255559, 0.427000000]: Loading sub-controller 'panda_joint3_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint3_controller
[ INFO] [1589373060.115402469, 0.429000000]: Loading sub-controller 'panda_joint4_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint4_controller
[ INFO] [1589373060.118159965, 0.432000000]: Loading sub-controller 'panda_joint5_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint5_controller
[ INFO] [1589373060.121295095, 0.434000000]: Loading sub-controller 'panda_joint6_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint6_controller
[ INFO] [1589373060.123932673, 0.435000000]: Loading sub-controller 'panda_joint7_controller', Namespace: /panda_simulator/effort_joint_torque_controller/joints/panda_joint7_controller
Loaded 'panda_simulator/effort_joint_torque_controller'
[ INFO] [1589373060.128818274, 0.440000000]: Initializing JointArrayController(type:/panda_simulator/effort_joint_gravity_controller) with 7 joints.
[ INFO] [1589373060.128857629, 0.440000000]: Loading sub-controller 'panda_joint1_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint1_controller
[ INFO] [1589373060.129384631, 0.441000000]: Loading sub-controller 'panda_joint2_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint2_controller
[ INFO] [1589373060.129845600, 0.441000000]: Loading sub-controller 'panda_joint3_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint3_controller
[ INFO] [1589373060.130413756, 0.442000000]: Loading sub-controller 'panda_joint4_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint4_controller
[ INFO] [1589373060.130641145, 0.442000000]: Loading sub-controller 'panda_joint5_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint5_controller
[ INFO] [1589373060.130864990, 0.442000000]: Loading sub-controller 'panda_joint6_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint6_controller
[ INFO] [1589373060.131261754, 0.443000000]: Loading sub-controller 'panda_joint7_controller', Namespace: /panda_simulator/effort_joint_gravity_controller/joints/panda_joint7_controller
Loaded 'panda_simulator/effort_joint_gravity_controller'
[ INFO] [1589373060.137300799, 0.449000000]: Initializing JointArrayController(type:/panda_simulator/position_joint_position_controller) with 7 joints.
[ INFO] [1589373060.137339656, 0.449000000]: Loading sub-controller 'panda_joint1_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint1_controller
[ INFO] [1589373060.150615997, 0.462000000]: Loading sub-controller 'panda_joint2_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint2_controller
[ INFO] [1589373060.164725590, 0.477000000]: Loading sub-controller 'panda_joint3_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint3_controller
[ INFO] [1589373060.180456829, 0.493000000]: Loading sub-controller 'panda_joint4_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint4_controller
[ INFO] [1589373060.193732702, 0.506000000]: Loading sub-controller 'panda_joint5_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint5_controller
[panda_gripper_controller_spawner_stopped-8] process has finished cleanly
log file: /home/local/.ros/log/97cc4ace-9515-11ea-beed-3c6aa7cb24ab/panda_gripper_controller_spawner_stopped-8*.log
[ INFO] [1589373060.206985540, 0.519000000]: Loading sub-controller 'panda_joint6_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint6_controller
[ INFO] [1589373060.220716225, 0.533000000]: Loading sub-controller 'panda_joint7_controller', Namespace: /panda_simulator/position_joint_position_controller/joints/panda_joint7_controller
Loaded 'panda_simulator/position_joint_position_controller'
Loaded 'panda_simulator/joint_state_controller'
Started ['panda_simulator/effort_joint_gravity_controller'] successfully
Started ['panda_simulator/position_joint_position_controller'] successfully
Started ['panda_simulator/joint_state_controller'] successfully
[controller_spawner_stopped-7] process has finished cleanly
log file: /home/local/.ros/log/97cc4ace-9515-11ea-beed-3c6aa7cb24ab/controller_spawner_stopped-7*.log
[controller_spawner-6] process has finished cleanly
log file: /home/local/.ros/log/97cc4ace-9515-11ea-beed-3c6aa7cb24ab/controller_spawner-6*.log
[ WARN] [1589373060.583040896]: Skipping virtual joint 'virtual_joint' because its child frame 'panda_link0' does not match the URDF frame 'world'
[robot_description-4] process has finished cleanly
log file: /home/local/.ros/log/97cc4ace-9515-11ea-beed-3c6aa7cb24ab/robot_description-4*.log
[ WARN] [1589373064.710131230, 5.018000000]: service '/get_planning_scene' not advertised yet. Continue waiting...
[ WARN] [1589373064.881109415, 5.188000000]: Waiting for position_joint_trajectory_controller/follow_joint_trajectory to come up
[ WARN] [1589373070.893925611, 11.188000000]: Waiting for position_joint_trajectory_controller/follow_joint_trajectory to come up
[ERROR] [1589373076.917137581, 17.188000000]: Action client not connected: position_joint_trajectory_controller/follow_joint_trajectory
[ INFO] [1589373077.152854482, 17.424000000]: Added GripperCommand controller for franka_gripper
[ INFO] [1589373077.152991742, 17.424000000]: Returned 1 controllers in list
[ INFO] [1589373077.172422093, 17.443000000]: Trajectory execution is managing controllers
Loading 'move_group/ApplyPlanningSceneService'...
Loading 'move_group/ClearOctomapService'...
Loading 'move_group/MoveGroupCartesianPathService'...
Loading 'move_group/MoveGroupExecuteTrajectoryAction'...
Loading 'move_group/MoveGroupGetPlanningSceneService'...
Loading 'move_group/MoveGroupKinematicsService'...
Loading 'move_group/MoveGroupMoveAction'...
Loading 'move_group/MoveGroupPickPlaceAction'...
Loading 'move_group/MoveGroupPlanService'...
Loading 'move_group/MoveGroupQueryPlannersService'...
Loading 'move_group/MoveGroupStateValidationService'...
[ INFO] [1589373077.263285832, 17.535000000]: 

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

[ INFO] [1589373077.263325353, 17.535000000]: MoveGroup context using planning plugin ompl_interface/OMPLPlanner
[ INFO] [1589373077.263339266, 17.535000000]: MoveGroup context initialization complete

You can start planning now!

^C[move_group-13] killing on exit
[gripper_action_server_emulator-12] killing on exit
[joint_trajectory_server_emulator-11] killing on exit
[topic_remap-10] killing on exit
[base_to_link0-5] killing on exit
[gazebo_gui-3] killing on exit
[robot_state_publisher-9] killing on exit
[gazebo-2] killing on exit
Traceback (most recent call last):
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/core.py", line 572, in signal_shutdown
    h()
  File "/home/local/ROS_packages/ws_moveit/src/panda_simulator/panda_sim_custom_action_server/scripts/start_joint_trajectory_server.py", line 61, in cleanup
    j.clean_shutdown()
  File "/home/local/ROS_packages/ws_moveit/src/panda_simulator/panda_sim_custom_action_server/src/panda_sim_custom_action_server/joint_trajectory_action_server.py", line 105, in clean_shutdown
    self._arm.exit_control_mode()
  File "/home/local/ROS_packages/ws_moveit/src/franka_ros_interface/franka_interface/src/franka_interface/arm.py", line 502, in exit_control_mode
    self.set_command_timeout(timeout)
  File "/home/local/ROS_packages/ws_moveit/src/franka_ros_interface/franka_interface/src/franka_interface/arm.py", line 537, in set_command_timeout
    self._pub_joint_cmd_timeout.publish(Float64(timeout))
  File "/opt/ros/melodic/lib/python2.7/dist-packages/rospy/topics.py", line 876, in publish
    raise ROSException("publish() to an unregistered() handle")
ROSException: publish() to an unregistered() handle
[gazebo_gui-3] escalating to SIGTERM
[gazebo-2] escalating to SIGTERM
[rosout-1] killing on exit
[master] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete

Cartesian Pose Control as directly supported by Panda (#39)

@justagist Hi, thank you very much for providing the panda interface.

I found a weird problem when I use provided demo "task_space_contrl_with_fri"(https://github.com/justagist/panda_simulator/blob/melodic-devel/panda_simulator_examples/scripts/task_space_control_with_fri.py). As you provided the controller, based on the position error in cartesian space, using a PD controller to calculate the desired force in cartesian space. Then use the torque controller in the joint space. I found it can not accurately control the cartesian pose by this controller. For example, when I only track motion (constant velocity)in the X direction (I set the delta_pos[0] =0.01 delta_pos[1] =0.0 delta_pos[2] =0.0 in the control_thread(). ).I expected the robot to only move along the X direction, but the robot also moves in the Z direction (the position in Z decreases).
When I test on other directions, it has the same issue. Both in the simulator and the real robot, the controller has the same problems. Thank you very much!

Originally posted by @siweiyong in #39 (reply in thread)

Moveit Demo

When running the Moveit Demo, rviz came out but disappeared quickly. I have run the Task-space control using Franka ROS Interface successfully.
I am sure I follow the Usage and I type these three commands in order in terminals but still find the bugs
roslaunch panda_gazebo panda_world.launch
roslaunch panda_sim_moveit sim_move_group.launch
roslaunch panda_simulator_examples demo_moveit.launch

The bug shows below:
[rviz_ubuntu_4376_5041817988713892492-1] process has died [pid 4525, exit code 127, cmd /opt/ros/melodic/lib/rviz/rviz -d /home/ye/ws_moveit/src/franka_ros_interface/franka_moveit/config/moveit_demo.rviz __name:=rviz_ubuntu_4376_5041817988713892492 __log:=/home/ye/.ros/log/142905d8-a403-11eb-aeb0-000c294926c2/rviz_ubuntu_4376_5041817988713892492-1.log]. log file: /home/ye/.ros/log/142905d8-a403-11eb-aeb0-000c294926c2/rviz_ubuntu_4376_5041817988713892492-1*.log

Error when running `roslaunch panda_sim_moveit sim_move_group.launch`

After running roslaunch panda_gazebo panda_world.launch, running roslaunch panda_sim_moveit sim_move_group.launch throws following errors and warnings:

[ WARN] [1637765133.010023688]: Skipping virtual joint 'virtual_joint' because its child frame 'panda_link0' does not match the URDF frame 'world'

[ERROR] [1637765133.314652012, 522.438000000]: Exception while loading planning adapter plugin 'default_planner_request_adapters/ResolveConstraintFrames': According to the loaded plugin descriptions the class default_planner_request_adapters/ResolveConstraintFrames with base class type planning_request_adapter::PlanningRequestAdapter does not exist. Declared types are default_planner_request_adapters/AddIterativeSplineParameterization default_planner_request_adapters/AddTimeOptimalParameterization default_planner_request_adapters/AddTimeParameterization default_planner_request_adapters/Empty default_planner_request_adapters/FixStartStateBounds default_planner_request_adapters/FixStartStateCollision default_planner_request_adapters/FixStartStatePathConstraints default_planner_request_adapters/FixWorkspaceBounds

[ WARN] [1637765138.586467174, 527.456000000]: Waiting for position_joint_trajectory_controller/follow_joint_trajectory to come up [ WARN] [1637765144.884922500, 533.457000000]: Waiting for position_joint_trajectory_controller/follow_joint_trajectory to come up [ERROR] [1637765151.501856397, 539.457000000]: Action client not connected: position_joint_trajectory_controller/follow_joint_trajectory [ WARN] [1637765157.075516047, 544.524000000]: Waiting for franka_gripper/gripper_action to come up [ WARN] [1637765163.391715395, 550.524000000]: Waiting for franka_gripper/gripper_action to come up [ERROR] [1637765169.698730447, 556.524000000]: Action client not connected: franka_gripper/gripper_action

Check #59 for my errors when running roslaunch panda_gazebo panda_world.launch.
I also have an issue with the roslaunch panda_simulator_examples demo_moveit.launch example, but I think it is related to the errors mentioned in here and #59. The issue I am having is that I can't use the plan feature although I used the same command and params as in this YouTube-video.

const class KDL::Joint’ has no member named ‘getInertia

There is a problem when I catkin_make about this package

/home/ye/finalyearproject/src/panda_simulator/panda_gazebo/src/kdl_methods.cpp: In member function ‘virtual int panda_gazebo::KDLMethods::RNECartToJnt(const KDL::JntArray&, const KDL::JntArray&, const KDL::JntArray&, const Wrenches&, KDL::JntArray&, KDL::Twist)’:/home/ye/finalyearproject/src/panda_simulator/panda_gazebo/src/kdl_methods.cpp:119:61: error: ‘const class KDL::Joint’ has no member named ‘getInertia’; did you mean ‘inertia’? torques(j)+=chain_.getSegment(i).getJoint().getInertia()*q_dotdot(j); // add torque from joint inertia
^~~~~~~~~~
inertia
/home/ye/finalyearproject/src/panda_simulator/panda_gazebo/src/kdl_methods.cpp: In member function ‘virtual int panda_gazebo::KDLMethods::JntToMass(const KDL::JntArray&, KDL::JntSpaceInertiaMatrix&)’:
/home/ye/finalyearproject/src/panda_simulator/panda_gazebo/src/kdl_methods.cpp:227:51: error: ‘const class KDL::Joint’ has no member named ‘getInertia’; did you mean ‘inertia’?
H(k,k)+=chain_.getSegment(i).getJoint().getInertia(); // add joint inertia
^~~~~~~~~~
inertia
panda_simulator/panda_gazebo/CMakeFiles/panda_gazebo_ros_control.dir/build.make:134: recipe for target 'panda_simulator/panda_gazebo/CMakeFiles/panda_gazebo_ros_control.dir/src/kdl_methods.cpp.o' failed`

I am trying to figure out what is wrong with this inertia? And if I replace the getInertia with inertia but it shows that
opt/ros/melodic/include/kdl/joint.hpp:202:16: note: declared private here

panda_gazebo_ros_control_plugin does not provide a working EffortJointInterface

When I launch the simulator using panda_world.launch panda_gazebo_ros_control_plugin gets loaded instead of default gazebo ros_control plugin.

It seems to provide EffortJointInterface for ros_control plugins. Correct me if I'm wrong.

Let's say I have a plugin which uses this interface
class TestController : public controller_interface::MultiInterfaceController<hardware_interface::EffortJointInterface>.
As usual I get the joint handles
joint_handles[i] = effort_joint_interface->getHandle(joint_names[i])).

They can be used for getting the for example the joint position with joint_handles_[i].getPosition(), but when I try to set effort with joint_handles_[i].setCommand(tau[i]) the robot does not move.

The same code works on the real robot and in an older revision of a similar project.

For this reason I'm unable to run the simulator with a variety of other ros controllers.

If you load the following yaml to the paramter server:

panda_arm_controller:
    type: effort_controllers/JointTrajectoryController
    joints:
        - panda_joint1
        - panda_joint2
        - panda_joint3
        - panda_joint4
        - panda_joint5
        - panda_joint6
        - panda_joint7

    gains:
        panda_joint1: { p: 12000, d: 50, i: 0.0, i_clamp: 10000 }
        panda_joint2: { p: 30000, d: 100, i: 0.02, i_clamp: 10000 }
        panda_joint3: { p: 18000, d: 50, i: 0.01, i_clamp: 1 }
        panda_joint4: { p: 18000, d: 70, i: 0.01, i_clamp: 10000 }
        panda_joint5: { p: 12000, d: 70, i: 0.01, i_clamp: 1 }
        panda_joint6: { p: 7000, d: 50, i: 0.01, i_clamp: 1 }
        panda_joint7: { p: 2000, d: 20, i: 0.0, i_clamp: 1 }

    constraints:
        goal_time: 2.0

    state_publish_rate: 25

And start panda_arm_controller with: rosrun controller_manager spawner panda_arm_controller
you can use rqt-joint-trajectory-controller GUI to move the robot in erdalpekel's panda_simulation, but not in this project.

Unable to identify any set of controllers

Hi! I tried to run the demo for testing the moveit planner interface with the simulated robot
roslaunch panda_simulator_examples demo_moveit.launch
However, it shows the following error.

[ERROR] [1604853219.157810719, 59.716000000]: Unable to identify any set of controllers that can actuate the specified joints: [ panda_joint1 panda_joint2 panda_joint3 panda_joint4 panda_joint5 panda_joint6 panda_joint7 ]
[ERROR] [1604853219.157828995, 59.716000000]: Known controllers and their joints:
controller 'franka_gripper' controls joints:
panda_finger_joint1
panda_finger_joint2

[ERROR] [1604853219.157858878, 59.716000000]: Apparently trajectory initialization failed

Another demo roslaunch panda_simulator_examples demo_task_space_control.launch
works fine.

Error while launching panda_world.launch

I am getting the error SetModelConfiguration service failed. Exiting. after I am trying to launch the panda_world.launch file. My device is Ubuntu 18.04 and I am using Gazebo9 in ROS Melodic.

Can anyone please guide me on how I can solve this problem?

Thank you.

Action client not connected. No controllers.

Hi, i get the following when running the first demo. Gazebo starts but moveit plan and execute fail. Space control demo starts but I am not sure what I am supposed to see, it's just a robot spawning.

[ WARN] [1623246837.082888209, 265.561000000]: Waiting for panda_arm_controller/follow_joint_trajectory to come up
[ WARN] [1623246843.260763153, 271.563000000]: Waiting for panda_arm_controller/follow_joint_trajectory to come up
[ERROR] [1623246849.457987399, 277.566000000]: Action client not connected: panda_arm_controller/follow_joint_trajectory
[ WARN] [1623246854.775775550, 282.669000000]: Waiting for panda_hand_controller/follow_joint_trajectory to come up
[ WARN] [1623246860.903231926, 288.669000000]: Waiting for panda_hand_controller/follow_joint_trajectory to come up
[ERROR] [1623246867.083942452, 294.673000000]: Action client not connected: panda_hand_controller/follow_joint_trajectory

After moveit plan or plan and execute:

[ERROR] [1623246874.713589285, 302.012000000]: Unable to identify any set of controllers that can actuate the specified joints: [ panda_joint1 panda_joint2 panda_joint3 panda_joint4 panda_joint5 panda_joint6 panda_joint7 ]
[ERROR] [1623246874.713613460, 302.012000000]: Known controllers and their joints:

[ERROR] [1623246874.713647697, 302.012000000]: Apparently trajectory initialization failed

Python script for Action Server fails

Hi,
i'm on U16.04 @ ROS kinetic
i followed the install instructions (i guess)
catkin_ws/src is:
CMakeLists.txt
franka_ros_interface
panda_robot
franka_panda_description
orocos_kinematics_dynamics
panda_simulator

during:
roslaunch panda_gazebo panda_world.launch
lots of stuff
then...
Starting context monitors...
[ INFO] [1592385325.219129687]: Starting scene monitor
[ INFO] [1592385325.225041161]: Listening to '/planning_scene'
[ INFO] [1592385325.225079605]: Starting world geometry monitor
publishing and latching message. Press ctrl-C to terminate
[ INFO] [1592385325.229153591]: Listening to '/collision_object' using message notifier with target frame '/world '
[ INFO] [1592385325.232247326]: Listening to '/planning_scene_world' for planning scene world geometry

[gripper_action_server_emulator-15] process has died [pid 19857, exit code -11, cmd /home/hdb/ai/catikin_ws/src/panda_simulator/panda_sim_custom_action_server/scripts/start_gripper_action_server.py __name:=gripper_action_server_emulator __log:=/home/hdb/.ros/log/12882122-b07b-11ea-9da0-185e0f9238df/gripper_action_server_emulator-15.log].
log file: /home/hdb/.ros/log/12882122-b07b-11ea-9da0-185e0f9238df/gripper_action_server_emulator-15*.log
[move_group-16] process has died [pid 19860, exit code -11, cmd /opt/ros/kinetic/lib/moveit_ros_move_group/move_group --debug __name:=move_group __log:=/home/hdb/.ros/log/12882122-b07b-11ea-9da0-185e0f9238df/move_group-16.log].
log file: /home/hdb/.ros/log/12882122-b07b-11ea-9da0-185e0f9238df/move_group-16*.log
[joint_trajectory_server_emulator-14] process has died [pid 19856, exit code -11, cmd /home/hdb/ai/catikin_ws/src/panda_simulator/panda_sim_custom_action_server/scripts/start_joint_trajectory_server.py __name:=joint_trajectory_server_emulator __log:=/home/hdb/.ros/log/12882122-b07b-11ea-9da0-185e0f9238df/joint_trajectory_server_emulator-14.log].
log file: /home/hdb/.ros/log/12882122-b07b-11ea-9da0-185e0f9238df/joint_trajectory_server_emulator-14*.log

this mentioned log files are empty
Any ideas?

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.