Closed Enzo-M closed 4 years ago
I have a similar issue: Could not find resource 'joint_back_right_steer' in 'hardware_interface::EffortJointInterface'.
Do you have installed the package ros-kinetic-effort-controllers?
Can you describe in detail about How you solve the controller manager problem? I meet the same. Thanks in advance.
Firstly, if you simply want a stable camera view at an appropriate angle, consider switching the PTZ Camera A's topic in RVIZ to /summit_xl_a/front_rgbd_camera/rgb/image_raw. If however, you want to be able to control the PTZ camera, read the rest of this post.
I found the problem to be in the package summit_xl_control. in the config file: summit_xl_control/config/summit_xl_a_control.yaml
I changed the "type" field of the "joint_pan_position_controller" and "joint_tilt_position_controller" from velocity_controllers/JointPositionController to position_controllers/JointPositionController. The issue is that the sensor uses the PositionJointInterface which requires the position_controllers to be loaded and not the velocity_controllers. However, This causes the following errors, due to the "gravity bug":
[ WARN] [1549347112.630936629, 0.002000000]: The default_robot_hw_sim plugin is using the Joint::SetPosition method without preserving the link velocity. [ WARN] [1549347112.630997293, 0.002000000]: As a result, gravity will not be simulated correctly for your model. [ WARN] [1549347112.631032544, 0.002000000]: Please set gazebo_pid parameters, switch to the VelocityJointInterface or EffortJointInterface, or upgrade to Gazebo 9. [ WARN] [1549347112.631067450, 0.002000000]: For details, see https://github.com/ros-simulation/gazebo_ros_pkgs/issues/612
To fix this, I changed from position_controllers/JointPositionController to effort_controllers/JointPositionController. An additional change is required then in the robotnik_sensores package. In .../robotnik_sensors/urdf/axis.urdf.xacro, the 4 harwareInterface tags have to be updated from hardware_interface/PositionJointInterface to hardware_interface/EffortJointInterface. Also in this file, set the pan_joint's lower and upper limits to -1.5708 and 1.5708 to avoid problems with the controllers angle error calculation. This changes the controller from a position_controllers to effort_controllers and gets rid of the gravity bug. Stable PID values for the effort_controller are: {p: 100.0, i: 0.0, d: 12.5}
Firstly, if you simply want a stable camera view at an appropriate angle, consider switching the PTZ Camera A's topic in RVIZ to /summit_xl_a/front_rgbd_camera/rgb/image_raw. If however, you want to be able to control the PTZ camera, read the rest of this post.
I found the problem to be in the package summit_xl_control. in the config file: summit_xl_control/config/summit_xl_a_control.yaml
I changed the "type" field of the "joint_pan_position_controller" and "joint_tilt_position_controller" from velocity_controllers/JointPositionController to position_controllers/JointPositionController. The issue is that the sensor uses the PositionJointInterface which requires the position_controllers to be loaded and not the velocity_controllers. However, This causes the following errors, due to the "gravity bug":
[ WARN] [1549347112.630936629, 0.002000000]: The default_robot_hw_sim plugin is using the Joint::SetPosition method without preserving the link velocity. [ WARN] [1549347112.630997293, 0.002000000]: As a result, gravity will not be simulated correctly for your model. [ WARN] [1549347112.631032544, 0.002000000]: Please set gazebo_pid parameters, switch to the VelocityJointInterface or EffortJointInterface, or upgrade to Gazebo 9. [ WARN] [1549347112.631067450, 0.002000000]: For details, see ros-simulation/gazebo_ros_pkgs#612
To fix this, I changed from position_controllers/JointPositionController to effort_controllers/JointPositionController. An additional change is required then in the robotnik_sensores package. In .../robotnik_sensors/urdf/axis.urdf.xacro, the 4 harwareInterface tags have to be updated from hardware_interface/PositionJointInterface to hardware_interface/EffortJointInterface. Also in this file, set the pan_joint's lower and upper limits to -1.5708 and 1.5708 to avoid problems with the controllers angle error calculation. This changes the controller from a position_controllers to effort_controllers and gets rid of the gravity bug. Stable PID values for the effort_controller are: {p: 100.0, i: 0.0, d: 12.5}
Has anyone fixed this issue using this solution? I am currently facing the same issue and the solution doesn't seem to work. The config file summit_xl_control/config/summit_xl_a_control.yaml is nowhere to be found. I used the setup instructions mentioned in the git. I am using ROS Kinetic and gazebo 7 on ubuntu 16.04
Hello,
My kernel and distro :
Linux version 4.4.0-75-generic (buildd@lgw01-21) (gcc version 5.4.0 20160609 (Ubuntu 5.4.0-6ubuntu1~16.04.4) ) #96-Ubuntu SMP Thu Apr 20 09:56:33 UTC 2017
I had a lot of errors with the controller_manager not finding the spawner (i solved it by git cloning the controller_manager repertory instead of using apt_get) during the launch.
But now i have other problems on the initialization of different joints of the robot. I don't know how to solve these errors so I'm here for some help.
My terminal output when launching Summit XL simulation:
enzo@cncr-2:~/catkin_ws$ roslaunch summit_xl_sim_bringup summit_xl_complete.launch ... logging to /home/enzo/.ros/log/906b4478-30b0-11e7-b728-104a7db141f8/roslaunch-cncr-2-18633.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: Traditional processing is deprecated. Switch to --inorder processing! To check for compatibility of your document, use option --check-order. For more infos, see http://wiki.ros.org/xacro#Processing_Order xacro.py is deprecated; please use xacro instead started roslaunch server http://cncr-2:34725/
SUMMARY
PARAMETERS
NODES / gazebo (gazebo_ros/gzserver) gazebo_gui (gazebo_ros/gzclient) ps3_joy (joy/joy_node) robot_state_publisher (robot_state_publisher/robot_state_publisher) summit_xl_pad (summit_xl_pad/summit_xl_pad) summit_xl_robot_control (summit_xl_robot_control/summit_xl_robot_control) twist_mux (twist_mux/twist_mux) urdf_spawner (gazebo_ros/spawn_model) /summit_xl/ controller_spawner (controller_manager/spawner)
ROS_MASTER_URI=http://localhost:11311
core service [/rosout] found process[summit_xl/controller_spawner-1]: started with pid [18654] process[robot_state_publisher-2]: started with pid [18655] process[twist_mux-3]: started with pid [18656] process[ps3_joy-4]: started with pid [18657] process[summit_xl_pad-5]: started with pid [18671] process[gazebo-6]: started with pid [18683] process[gazebo_gui-7]: started with pid [18686] process[urdf_spawner-8]: started with pid [18702] process[summit_xl_robot_control-9]: started with pid [18715] [ INFO] [1493892061.156021824]: summit_xl_robot_control_node - Init [ INFO] [1493892061.160479087]: Robot Model : summitxl [ INFO] [1493892061.215892612]: Opened joystick: /dev/input/js0. deadzone: 0.120000. [ INFO] [1493892061.224011217]: summit_xl_wheeldiameter = 0.25 [ INFO] [1493892061.224059378]: summit_xl_d_tracksm = 1.00 [ INFO] [1493892061.226181772]: NOT PUBLISHING odom->base_footprint tf [ INFO] [1493892061.277524508]: SummitXLPad num_ofbuttons = 15 [ INFO] [1493892061.277593914]: bREG 0 [ INFO] [1493892061.277608156]: bREG 1 [ INFO] [1493892061.277618105]: bREG 2 [ INFO] [1493892061.277628738]: bREG 3 [ INFO] [1493892061.277640441]: bREG 4 [ INFO] [1493892061.277648647]: bREG 5 [ INFO] [1493892061.277657034]: bREG 6 [ INFO] [1493892061.277666054]: bREG 7 [ INFO] [1493892061.277674003]: bREG 8 [ INFO] [1493892061.277681671]: bREG 9 [ INFO] [1493892061.277693802]: bREG 10 [ INFO] [1493892061.277704145]: bREG 11 [ INFO] [1493892061.277714539]: bREG 12 [ INFO] [1493892061.277724397]: bREG 13 [ INFO] [1493892061.277734816]: bREG 14
SpawnModel script started [ INFO] [1493892061.378262779]: Finished loading Gazebo ROS API Plugin. [ INFO] [1493892061.378878944]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting... [INFO] [1493892061.461683, 0.000000]: Loading model XML from ros parameter [INFO] [1493892061.464889, 0.000000]: Waiting for service /gazebo/spawn_urdf_model [INFO] [1493892061.532412, 0.000000]: Controller Spawner: Waiting for service /summit_xl/controller_manager/load_controller [ INFO] [1493892061.595727038, 0.022000000]: waitForService: Service [/gazebo/set_physics_properties] is now available. [ INFO] [1493892061.620291917, 0.046000000]: Physics dynamic reconfigure ready. [INFO] [1493892061.767566, 0.189000]: Calling service /gazebo/spawn_urdf_model
[ INFO] [1493892062.394323217, 0.360000000]: Laser Plugin: Using the 'robotNamespace' param: '/' [ INFO] [1493892062.394370684, 0.360000000]: Starting Laser Plugin (ns = /)! [ INFO] [1493892062.396785824, 0.360000000]: Laser Plugin (ns = /), set to ""
[INFO] [1493892062.403627, 0.360000]: Spawn status: SpawnModel: Successfully spawned entity
[ INFO] [1493892062.442239353, 0.360000000]: Loading gazebo_ros_control plugin
[ INFO] [1493892062.442374782, 0.360000000]: Starting gazebo_ros_control plugin in namespace: /summit_xl
[ INFO] [1493892062.443113973, 0.360000000]: gazebo_ros_control plugin is waiting for model URDF in parameter [/robot_description] on the ROS param server.
[ WARN] [1493892062.601182266, 0.360000000]: Deprecated syntax, please prepend 'hardware_interface/' to 'EffortJointInterface' within the tag in joint 'joint_front_right_wheel'.
[ WARN] [1493892062.602135467, 0.360000000]: Deprecated syntax, please prepend 'hardware_interface/' to 'EffortJointInterface' within the tag in joint 'joint_front_left_wheel'.
[ WARN] [1493892062.603062641, 0.360000000]: Deprecated syntax, please prepend 'hardware_interface/' to 'EffortJointInterface' within the tag in joint 'joint_back_left_wheel'.
[ WARN] [1493892062.603548086, 0.360000000]: Deprecated syntax, please prepend 'hardware_interface/' to 'EffortJointInterface' within the tag in joint 'joint_back_right_wheel'.
[ INFO] [1493892062.608249980, 0.360000000]: Loaded gazebo_ros_control.
[ WARN] [1493892062.611388272, 0.360000000]: GazeboRosSkidSteerDrive Plugin (ns = /summit_xl/) missing , defaults to 0.000100
[ WARN] [1493892062.611416739, 0.360000000]: GazeboRosSkidSteerDrive Plugin (ns = /summit_xl/) missing , defaults to 0.000100
[ WARN] [1493892062.611431970, 0.360000000]: GazeboRosSkidSteerDrive Plugin (ns = /summit_xl/) missing , defaults to 0.010000
[ INFO] [1493892062.611492086, 0.360000000]: Starting GazeboRosSkidSteerDrive Plugin (ns = /summit_xl/)!
[urdf_spawner-8] process has finished cleanly
log file: /home/enzo/.ros/log/906b4478-30b0-11e7-b728-104a7db141f8/urdf_spawner-8.log
[INFO] [1493892062.739651, 0.413000]: Controller Spawner: Waiting for service /summit_xl/controller_manager/switch_controller
[INFO] [1493892062.742544, 0.416000]: Controller Spawner: Waiting for service /summit_xl/controller_manager/unload_controller
[INFO] [1493892062.744441, 0.418000]: Loading controller: joint_blw_velocity_controller
[INFO] [1493892062.803965, 0.477000]: Loading controller: joint_brw_velocity_controller
[INFO] [1493892062.808881, 0.482000]: Loading controller: joint_frw_velocity_controller
[INFO] [1493892062.813744, 0.487000]: Loading controller: joint_flw_velocity_controller
[INFO] [1493892062.818717, 0.492000]: Loading controller: joint_pan_position_controller
[ERROR] [1493892062.844599970, 0.518000000]: Exception thrown while initializing controller joint_pan_position_controller.
Could not find resource 'joint_camera_pan' in 'hardware_interface::EffortJointInterface'.
[ERROR] [1493892062.844636121, 0.518000000]: Initializing controller 'joint_pan_position_controller' failed
Segmentation fault (core dumped)
[gazebo_gui-7] process has died [pid 18686, exit code 139, cmd /opt/ros/kinetic/lib/gazebo_ros/gzclient __name:=gazebo_gui __log:=/home/enzo/.ros/log/906b4478-30b0-11e7-b728-104a7db141f8/gazebo_gui-7.log].
log file: /home/enzo/.ros/log/906b4478-30b0-11e7-b728-104a7db141f8/gazebo_gui-7.log
[ERROR] [1493892063.850324, 1.518000]: Failed to load joint_pan_position_controller [INFO] [1493892063.850689, 1.518000]: Loading controller: joint_tilt_position_controller [ERROR] [1493892063.884128057, 1.552000000]: Exception thrown while initializing controller joint_tilt_position_controller. Could not find resource 'joint_camera_tilt' in 'hardware_interface::EffortJointInterface'. [ERROR] [1493892063.884165944, 1.552000000]: Initializing controller 'joint_tilt_position_controller' failed [ INFO] [1493892064.284628089, 1.951000000]: SummitXLControllerClass::starting [ERROR] [1493892064.888017, 2.552000]: Failed to load joint_tilt_position_controller [INFO] [1493892064.888350, 2.552000]: Loading controller: joint_read_state_controller [INFO] [1493892064.927273, 2.591000]: Controller Spawner: Loaded controllers: joint_blw_velocity_controller, joint_brw_velocity_controller, joint_frw_velocity_controller, joint_flw_velocity_controller, joint_read_state_controller [INFO] [1493892064.930122, 2.594000]: Started controllers: joint_blw_velocity_controller, joint_brw_velocity_controller, joint_frw_velocity_controller, joint_flw_velocity_controller, joint_read_statecontroller [ INFO] [1493892065.284760983, 2.947000000]: SummitXLControllerClass::starting_
I don't understand why my gazebo is constantly dying.
Thank you for helping me please.