Giter Site home page Giter Site logo

robotnikautomation / summit_xl_sim Goto Github PK

View Code? Open in Web Editor NEW
65.0 16.0 39.0 11.85 MB

Packages for the simulation of the Summit XL, Summit XL HL and Summit-X (including X-WAM) robots

License: BSD 2-Clause "Simplified" License

CMake 18.69% Dockerfile 78.23% Shell 3.08%
robots summit-xl ros gazebo gazebo-ros gazebo-simulator melodic kinetic docker ros-melodic ros-kinetic

summit_xl_sim's Introduction

summit_xl_sim

Packages for the simulation of the Summit XL

This packages contains:

summit_xl_gazebo

Launch files and world files to start the models in gazebo

summit_xl_sim_bringup

Launch files that launch the complete simulation of the robot/s

Simulating Summit XL

This simulation has been tested using Gazebo 9 version.

Installation and run instruccions

1. Install the following dependencies:

To facilitate the installation you can use the vcstool:

sudo apt-get install -y python3-vcstool

2. Create a workspace and clone the repository:

mkdir catkin_ws
cd catkin_ws

Install the latest version of the simulation:

vcs import --input https://raw.githubusercontent.com/RobotnikAutomation/summit_xl_sim/melodic-devel/repos/summit_xl_sim_devel.repos

Install the ROS dependencies

rosdep install --from-paths src --ignore-src --skip-keys="summit_xl_robot_control marker_mapping robotnik_locator robotnik_pose_filter robotnik_gazebo_elevator" -y -r

3. Compile:

catkin build
source devel/setup.bash

ONLY: if catkin build doesn't work: The package catkin-tools is need to compile with catkin build:

sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu `lsb_release -sc` main" > /etc/apt/sources.list.d/ros-latest.list'
wget http://packages.ros.org/ros.key -O - | sudo apt-key add -
sudo apt-get update
sudo apt-get install python-catkin-tools

4. Launch Summit XL simulation (1 robot by default, up to 3 robots):

Summit XL:

roslaunch summit_xl_sim_bringup summit_xl_complete.launch

Summit XL with Trossen Arm

roslaunch summit_xl_sim_bringup summit_xl_complete.launch default_xacro:=summit_xl_tix_std.urdf.xacro launch_arm_a:=true arm_manufacturer_a:=trossen arm_model_a:=vx300s

Launch moveit to plan trajectories:

ROS_NAMESPACE=robot roslaunch summit_xl_vx300s_moveit_config demo.launch

Summit XL with Kinova Arm

roslaunch summit_xl_sim_bringup summit_xl_complete.launch default_xacro:=summit_xl_gen_std.urdf.xacro launch_arm_a:=true arm_manufacturer_a:=kinova arm_model_a:=j2s7s300 amcl_and_mapserver_a:=false move_base_robot_a:=false

Note: in this configuration the robot has not laser, therefore the amcl is turned off. When Rviz is opened, change robot_map to robot_odom in fixed_frame in order to visualize the robot.

or Summit XL Steel:

roslaunch summit_xl_sim_bringup summit_xls_complete.launch

Optional general arguments:

<arg name="launch_rviz" default="true"/>
<arg name="gazebo_world" default="$(find summit_xl_gazebo)/worlds/summit_xl_office.world"/>
<arg name="omni_drive" default="false"/> (only for Summit XL)
<arg name="use_gpu_for_simulation" default="false"/>

By default the Gazebo plugin Planar Move to ignore the physics of the wheels + the skid steering kinematics. In case you want to disable this plugin, set the following arguments:

roslaunch summit_xl_sim_bringup summit_xl_complete.launch \
  ros_planar_move_plugin:=false \
  omni_drive:=false

Optional robot arguments:

<!--arguments for each robot (example for robot A)-->
<arg name="id_robot_a" default="robot"/>
<arg name="launch_robot_a" default="true"/>
<arg name="map_file_a" default="willow_garage/willow_garage.yaml"/>
<arg name="localization_robot_a" default="false"/>
<arg name="gmapping_robot_a" default="false"/>
<arg name="amcl_and_mapserver_a" default="true"/>
<arg name="x_init_pose_robot_a" default="0" />
<arg name="y_init_pose_robot_a" default="0" />
<arg name="z_init_pose_robot_a" default="0" />
<arg name="xacro_robot_a" default="summit_xl_std.urdf.xacro"/>
  • Example to launch simulation with 3 Summit XL robots:
roslaunch summit_xl_sim_bringup summit_xl_complete.launch \
  launch_robot_b:=true \
  launch_robot_c:=true
  • Example to launch simulation with 1 Summit XL robot with navigation:
roslaunch summit_xl_sim_bringup summit_xl_complete.launch \
  move_base_robot_a:=true \
  amcl_and_mapserver_a:=true

Enjoy! You can use the topic ${id_robot}/robotnik_base_control/cmd_vel to control the Summit XL robot or send simple goals using /${id_robot}/move_base_simple/goal

Docker usage

Installation of required files

Intel GPU

Nvidia GPU

Usage

git clone https://github.com/RobotnikAutomation/summit_xl_sim.git
cd summit_xl_sim
git checkout melodic-devel
export ROS_BU_PKG="summit_xl_sim_bringup"
export ROS_BU_LAUNCH="summit_xl_complete.launch"
nvidia-smi &>/dev/null \
&& ln -sf docker-compose-nvidia.yml docker-compose.yml \
|| ln -sf docker-compose-intel.yml docker-compose.yml
docker compose up

Selecting the robot model

You can select the robot, the launch file of package using the optional arguments on launch By default the selected robot is summit_xl

Summit XL GEN

export ROS_BU_PKG="summit_xl_sim_bringup"
export ROS_BU_LAUNCH="summit_xl_gen_complete.launch"
docker compose up

Summit XLS

export ROS_BU_PKG="summit_xl_sim_bringup"
export ROS_BU_LAUNCH="summit_xls_complete.launch"
docker compose up

Manual Build

If you wish to build the image without launching the simulation use the following commands:

cd docker
docker compose build

Notes

This is docker requires a graphical interface

  • In order to exit you have to 2 options

  • The ROS_MASTER_URI is accessible outside the container, so in the host any ros command should work

  • You could also run a roscore previous to launch the simulation in order to have some processes on the host running

  • if you want to enter on the container use the following command in another terminal

  1. Close gazebo and rviz and wait a bit

  2. execute in another terminal:

    docker container rm --force summit_xl_sim_instance

Notes

  • This is docker requires a graphical interface

  • The ROS_MASTER_URI is accessible outside the container, so in the host any ros command should work

  • You could also run a roscore previous to launch the simulation in order to have some processes on the host running

  • if you want to enter on the container use the following command in another terminal

    docker container exec -it docker-base-1 bash
  • In order to exit you have to 2 options

  1. Close gazebo and rviz and wait a bit

  2. execute in another terminal in the same folder than the docker-compose.yml:

    docker compose down

summit_xl_sim's People

Contributors

alex-arnal avatar alvarovillena avatar asoriano1 avatar awesomebytes avatar carlos3dx avatar dani-carbonell avatar ggari-robotnik avatar jgomezgadea avatar jmnavarrete avatar jorgearino avatar marbosjo avatar martamillet avatar mcanter0 avatar msaurah avatar ndiazrey avatar rguzman1 avatar robert-ros avatar romanrobotnik 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

Watchers

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

summit_xl_sim's Issues

Issue when catkin_make

Hello,

I git cloned your repertory to my catkin_ws with :
git clone -b kinetic-devel https://github.com/RobotnikAutomation/summit_xl_sim/
and then when executing :
catkin_make
i got this error :

CMake Error at /opt/ros/kinetic/share/catkin/cmake/catkinConfig.cmake:83 (find_package):
Could not find a package configuration file provided by "gazebo_ros" with
any of the following names:

gazebo_rosConfig.cmake
gazebo_ros-config.cmake

Add the installation prefix of "gazebo_ros" to CMAKE_PREFIX_PATH or set
"gazebo_ros_DIR" to a directory containing one of the above files. If
"gazebo_ros" provides a separate development package or SDK, be sure it has
been installed.
Call Stack (most recent call first):
summit_xl_sim/summit_xl_gazebo/CMakeLists.txt:5 (find_package)

-- Configuring incomplete, errors occurred!
See also "/home/menassolenzo/catkin_ws/build/CMakeFiles/CMakeOutput.log".
See also "/home/menassolenzo/catkin_ws/build/CMakeFiles/CMakeError.log".
Makefile:1830: recipe for target 'cmake_check_build_system' failed
make: *** [cmake_check_build_system] Error 1
Invoking "make cmake_check_build_system" failed

Running simulation of the Summit X_WAM platform

Hello, I work in a research lab at the Georgia Institute of Technology in the US, and we have a summit x-wam robot, this one here:

https://www.robotnik.eu/new-mobile-manipulator-concept-x-wam/

We're trying to get it up and running again in order to develop and test some of our algorithms in stochastic optimal control and machine learning. We need to get a simulation environment to test with. Right now we have the following repos cloned in our catkin workspace

  • summit_xl_sim
  • summit_xl_common
  • summit_x_common
  • summit_x_robot
  • robotnik_sensors
  • robotnik_msgs
  • robot_localization_utils
  • costmap_prohibition_layer

Will we be able to run simulations for the summit x-wam, including the omni-directional wheels, scissor mechanism, and manipulator? Are the resources available and functional for this? I've tried running some of the summit_xl_sim scenarios and I'm having compatibility issues with xacro and the urdf models, but we can always work through those. We just want to make sure that it's even possible to get a simulation up and running of the x-wam robot.

Thanks!

Bad navigation behavior

Hi, I have downloadaed an installed the packages following the instructions. When I run the simulations with navigation turned on, the robot behaves poorly, barely following it's planning trajectory. It seems it has a lot of trouble turning.

In this example, it has to follow a pretty straight trajectory, which should take it only a few seconds, but in stead it goes on straight, just to stop and turn very slowly, never quite reaching it's goal. Also, at the end the odometry is quite poor, as it is almost 90ยบ from it's real orientation.

screenshot from 2018-06-15 14-56-53

I have tried tunning some parameters, in navigation, the controllers... but I didn't achieve anything. Is this... normal? Have I maybe missed some step in the process?

Tuning PID in gazebo for SUMMIT XL Robot

Hi all,
We are trying to move SUMMIT XL robot in a straight line and circle in gazebo. In connection with this task, we used PID controller for wheel actuation joints to obtain accurate output motion and response.

For this purpose, we have changed the launch files of summit xl robot to tune the pid gains as shown below:


  <param name="/robot/gazebo_ros_control/pid_gains/$(arg prefix)front_left_wheel_joint/p" type="double" value="$(arg p)" />
  <param name="/robot/gazebo_ros_control/pid_gains/$(arg prefix)front_left_wheel_joint/i" type="double" value="$(arg i)" />
  <param name="/robot/gazebo_ros_control/pid_gains/$(arg prefix)front_left_wheel_joint/d" type="double" value="$(arg d)" />

  <param name="/robot/gazebo_ros_control/pid_gains/robot_back_right_wheel_joint/p" type="double" value="$(arg p)" />
  <param name="/robot/gazebo_ros_control/pid_gains/robot_back_right_wheel_joint/i" type="double" value="$(arg i)" />
  <param name="/robot/gazebo_ros_control/pid_gains/robot_back_right_wheel_joint/d" type="double" value="$(arg d)" />

  <param name="/robot/gazebo_ros_control/pid_gains/robot_back_left_wheel_joint/p" type="double" value="$(arg p)" />
  <param name="/robot/gazebo_ros_control/pid_gains/robot_back_left_wheel_joint/i" type="double" value="$(arg i)" />
  <param name="/robot/gazebo_ros_control/pid_gains/robot_back_left_wheel_joint/d" type="double" value="$(arg d)" />

However, the outputs are not desirable. The effect of d-gain is to mitigate the oscillations in response patterns of velocity, which is not happening.

image

In both planar and differential drive plugins, it can be seen that the response patterns oscillates, and it doesn't reduce even by increasing d-gain.

For some values of p (>=100) with i & d being zero, the robot moves/ oscillates around the finish point, although the motion is complete.

Please see the below gif where the robot moves in a circle and after reaching the finsh point, it oscillates about that point (p=100, i=0, d=0)

https://lh3.googleusercontent.com/-K-9B7Z6JKZM/XuSAtjxyopI/AAAAAAAAAzQ/GQo42t1xkRMtWb1GvtGmQmNNkxQo14H0QCK8BGAsYHg/s0/gif2.gif

With reduced value of p, this behavior vanishes, but the circle formed is of greater dimension than the actual...
With both p and d enabled, the robot begins to oscillate at the start itself.
p:100 i:0 d:10
https://lh3.googleusercontent.com/-K-0_LrgqTR0/XuSBNUx0urI/AAAAAAAAAzo/x-gdf77g14cqAmhhKIurU7czDIrGK_5TgCK8BGAsYHg/s0/gif3.gif

We are being confused with this, as these behaviours are new and not getting aligned with our knowledge on PID Control theory. Is the summit xl being properly configured for manual tuning of PID gains in simulation? Is there any problem in this configuration?
Or, do we need to change the approach we used? Is it preferrable to do PID tuning in gazebo?

Any help on this issue would be appreciated.

Docker, rosdep update not working because of end-of-live

Following the description to use the Docker within an Ubuntu 20.04 host, I got the following error while running docker-compose up

...
ERROR: the following packages/stacks could not have their rosdep keys resolved to system dependencies:
kinova_msgs: Cannot locate rosdep definition for [catkin]
...

I could resolve the issue by adding the option --include-eol-distros to rosdep update within the Dockerfile.

Robot localization using aruco marker in gazebo

We are trying to localize the robot in gazebo using aruco marker. We have successfully loaded the marker into gazebo, detected it, and obtained the transformation between camera frame and marker frame using aruco_ros (https://github.com/pal-robotics/aruco_ros) package. The transform between them obtained from tf package is in excellent agreement with the one obtained from the package.
image

However, the physical location of marker frame is not the same when we visualize it in RviZ. Please see the image below
image

As shown above, the location of marker frame in RViz does not match with that of gazebo. This really confuses us because we are not clear which dictates the physical location of marker in reality

Any help on this issue would be appreciated.
Thanks

summit_xl_control crashes as soon as I launch

I get the following error as soon as I launch the summit_xl_control to get a link between odom and base_link.
[ INFO] [1441269232.456259714, 0.241000000]: Physics dynamic reconfigure ready.
[ INFO] [1441269232.585299607, 0.371000000]: SummitXLControllerClass::starting
[summit_xl/summit_xl_robot_control-10] process has died [pid 13889, exit code -11, cmd /home/toshiba/catkin_ws/devel/lib/summit_xl_robot_control/summit_xl_robot_control __name:=summit_xl_robot_control __log:=/home/toshiba/.ros/log/664a1aea-5216-11e5-b082-e06995342d97/summit_xl-summit_xl_robot_control-10.log].
log file: /home/toshiba/.ros/log/664a1aea-5216-11e5-b082-e06995342d97/summit_xl-summit_xl_robot_control-10*.log

My tf tree is shown below. I have 2 robots. one husky and one summit so I am using a namespace for summit as summit_xl. I dont understand why is there a tf from /gazebo from /map->/odom but not via the summit_controller_node.

frames-1

Gazebo simulation- Wheels of SUMMIT XL robot not rotating in gazebo

We are trying to move the summit xl robot in straight line in gazebo. Although the robot moves, the wheel doesn't rotate. The following errors pop up whenever we launch the corresponding launch file.
Screenshot from 2020-05-25 12-15-05

It seems the yaml file misses the pid parameters for wheel joints. Although we tried to give the PID parameters to these joints, still the error persists and the wheels are not rotating.

Any help for this issue would be appreciated. Thanks

The model placed on gazebo is not moving with cmd_vel topics.

Hello.
I am following the guide descripted on link.

I clone three repository on my catkin_ws directroy.
I did two step to run 'summit_xl_sim' like this.

$ cd PATH
$ rosdep install --from-paths src --ignore-src -r -y
$ roslaunch summit_xl_sim_bringup summit_xl_complete.launch

And I could see the model on Rviz and Gazebo.
Here is the log and screenshots.

$ roslaunch summit_xl_sim_bringup summit_xl_complete.launch
... logging to /home/msi-h310/.ros/log/859bd69e-6046-11e9-9ef6-309c23b89cf6/roslaunch-msih310-H310-Gaming-Trident3-MS-B920-18298.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.

started roslaunch server http://msih310-H310-Gaming-Trident3-MS-B920:34371/

SUMMARY
========

PARAMETERS
 * /rosdistro: kinetic
 * /rosversion: 1.12.14
 * /summit_xl_a/joint_pan_position_controller/joint: summit_xl_a_front...
 * /summit_xl_a/joint_pan_position_controller/pid/d: 10.0
 * /summit_xl_a/joint_pan_position_controller/pid/i: 0.01
 * /summit_xl_a/joint_pan_position_controller/pid/p: 100.0
 * /summit_xl_a/joint_pan_position_controller/type: velocity_controll...
 * /summit_xl_a/joint_read_state_controller/publish_rate: 100.0
 * /summit_xl_a/joint_read_state_controller/type: joint_state_contr...
 * /summit_xl_a/joint_tilt_position_controller/joint: summit_xl_a_front...
 * /summit_xl_a/joint_tilt_position_controller/pid/d: 10.0
 * /summit_xl_a/joint_tilt_position_controller/pid/i: 0.01
 * /summit_xl_a/joint_tilt_position_controller/pid/p: 100.0
 * /summit_xl_a/joint_tilt_position_controller/type: velocity_controll...
 * /summit_xl_a/robot_description: <?xml version="1....
 * /summit_xl_a/robotnik_base_control/angular/z/has_acceleration_limits: True
 * /summit_xl_a/robotnik_base_control/angular/z/has_velocity_limits: True
 * /summit_xl_a/robotnik_base_control/angular/z/max_acceleration: 6.0
 * /summit_xl_a/robotnik_base_control/angular/z/max_velocity: 6.0
 * /summit_xl_a/robotnik_base_control/base_frame_id: summit_xl_a_base_...
 * /summit_xl_a/robotnik_base_control/cmd_vel_timeout: 0.25
 * /summit_xl_a/robotnik_base_control/enable_odom_tf: True
 * /summit_xl_a/robotnik_base_control/left_wheel: ['summit_xl_a_fro...
 * /summit_xl_a/robotnik_base_control/linear/x/has_acceleration_limits: True
 * /summit_xl_a/robotnik_base_control/linear/x/has_velocity_limits: True
 * /summit_xl_a/robotnik_base_control/linear/x/max_acceleration: 6.0
 * /summit_xl_a/robotnik_base_control/linear/x/max_velocity: 3.0
 * /summit_xl_a/robotnik_base_control/linear/x/min_acceleration: -6.0
 * /summit_xl_a/robotnik_base_control/linear/x/min_velocity: -3.0
 * /summit_xl_a/robotnik_base_control/odom_frame_id: summit_xl_a_odom
 * /summit_xl_a/robotnik_base_control/pose_covariance_diagonal: [0.001, 0.001, 10...
 * /summit_xl_a/robotnik_base_control/publish_rate: 50.0
 * /summit_xl_a/robotnik_base_control/right_wheel: ['summit_xl_a_fro...
 * /summit_xl_a/robotnik_base_control/twist_covariance_diagonal: [0.001, 0.001, 10...
 * /summit_xl_a/robotnik_base_control/type: diff_drive_contro...
 * /summit_xl_a/robotnik_base_control/wheel_radius: 0.11
 * /summit_xl_a/robotnik_base_control/wheel_radius_multiplier: 1.0
 * /summit_xl_a/robotnik_base_control/wheel_separation: 0.543
 * /summit_xl_a/robotnik_base_control/wheel_separation_multiplier: 1.0
 * /summit_xl_a/twist_mux/locks: [{'topic': 'summi...
 * /summit_xl_a/twist_mux/topics: [{'topic': 'pad_t...
 * /use_sim_time: True

NODES
  /summit_xl_a/
    controller_spawner (controller_manager/spawner)
    robot_state_publisher (robot_state_publisher/robot_state_publisher)
    twist_marker (twist_mux/twist_marker)
    twist_mux (twist_mux/twist_mux)
    urdf_spawner_summit_model (gazebo_ros/spawn_model)
  /
    gazebo (gazebo_ros/gzserver)
    gazebo_gui (gazebo_ros/gzclient)
    rviz (rviz/rviz)

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

setting /run_id to 859bd69e-6046-11e9-9ef6-309c23b89cf6
process[rosout-1]: started with pid [18324]
started core service [/rosout]
process[summit_xl_a/robot_state_publisher-2]: started with pid [18348]
process[summit_xl_a/urdf_spawner_summit_model-3]: started with pid [18349]
process[summit_xl_a/controller_spawner-4]: started with pid [18350]
process[summit_xl_a/twist_mux-5]: started with pid [18357]
process[summit_xl_a/twist_marker-6]: started with pid [18366]
process[gazebo-7]: started with pid [18381]
process[gazebo_gui-8]: started with pid [18396]
process[rviz-9]: started with pid [18423]
[ INFO] [1555419162.975758060]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1555419162.975860355]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1555419162.976127423]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1555419162.976647928]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[INFO] [1555419162.990079, 0.000000]: Controller Spawner: Waiting for service controller_manager/load_controller
SpawnModel script started
[INFO] [1555419163.239468, 0.000000]: Loading model XML from ros parameter
[INFO] [1555419163.241991, 0.000000]: Waiting for service /gazebo/spawn_urdf_model
[INFO] [1555419164.748111, 0.000000]: Calling service /gazebo/spawn_urdf_model
[ INFO] [1555419164.791177316, 0.022000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
Qt: Cannot set locale modifiers: 
[ INFO] [1555419165.448072136, 0.064000000]: Laser Plugin: Using the 'robotNamespace' param: '/summit_xl_a/'
[ INFO] [1555419165.448106827, 0.064000000]: Starting Laser Plugin (ns = /summit_xl_a/)
[ INFO] [1555419165.448836843, 0.064000000]: Laser Plugin (ns = /summit_xl_a/)  <tf_prefix_>, set to "/summit_xl_a"
[libprotobuf ERROR google/protobuf/message_lite.cc:123] Can't parse message of type "gazebo.msgs.Packet" because it is missing required fields: stamp, type, serialized_data
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
[ INFO] [1555419165.592017736, 0.064000000]: Camera Plugin: Using the 'robotNamespace' param: '/summit_xl_a/'
Master Unknown message type[] From[34818]
[libprotobuf ERROR google/protobuf/message_lite.cc:123] Can't parse message of type "gazebo.msgs.Packet" because it is missing required fields: stamp, type, serialized_data
Master Unknown message type[] From[34818]
[libprotobuf ERROR google/protobuf/message_lite.cc:123] Can't parse message of type "gazebo.msgs.Packet" because it is missing required fields: stamp, type, serialized_data
Master Unknown message type[] From[34818]
[ INFO] [1555419165.595342079, 0.064000000]: Camera Plugin (ns = /summit_xl_a/)  <tf_prefix_>, set to "/summit_xl_a"
[INFO] [1555419165.597384, 0.064000]: Spawn status: SpawnModel: Successfully spawned entity
[ INFO] [1555419165.598077336, 0.064000000]: Camera Plugin: Using the 'robotNamespace' param: '/summit_xl_a/'
[ INFO] [1555419165.602217472, 0.064000000]: Camera Plugin (ns = /summit_xl_a/)  <tf_prefix_>, set to "/summit_xl_a"
[libprotobuf ERROR google/protobuf/message_lite.cc:123] Can't parse message of type "gazebo.msgs.Packet" because it is missing required fields: stamp, type, serialized_data
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
Master Unknown message type[] From[34818]
[libprotobuf ERROR google/protobuf/message_lite.cc:123] Can't parse message of type "gazebo.msgs.Packet" because it is missing required fields: stamp, type, serialized_data
Master Unknown message type[] From[34818]
[ INFO] [1555419165.610421232, 0.064000000]: Physics dynamic reconfigure ready.
[libprotobuf ERROR google/protobuf/message_lite.cc:123] Can't parse message of type "gazebo.msgs.Packet" because it is missing required fields: stamp, type, serialized_data
Master Unknown message type[] From[34818]
[ INFO] [1555419165.742501315, 0.086000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1555419165.764930564, 0.105000000]: Physics dynamic reconfigure ready.
[summit_xl_a/urdf_spawner_summit_model-3] process has finished cleanly
log file: /home/msi-h310/.ros/log/859bd69e-6046-11e9-9ef6-309c23b89cf6/summit_xl_a-urdf_spawner_summit_model-3*.log
[WARN] [1555419193.114739, 25.727000]: Controller Spawner couldn't find the expected controller_manager ROS interface.
[summit_xl_a/controller_spawner-4] process has finished cleanly
log file: /home/msi-h310/.ros/log/859bd69e-6046-11e9-9ef6-309c23b89cf6/summit_xl_a-controller_spawner-4*.log

image
image

After this steps, I pub topics on other terminal.
But there is no any changes.

$ rostopic pub /summit_xl_a/robotnik_base_control/cmd_vel geometry_msgs/Twist "linear:
  x: 0.0
  y: 0.0
  z: 0.0
angular:
  x: 0.0
  y: 50.0
  z: 0.0" 
  1. What is the meaning of the error on Rviz?
  2. Did I miss something to do it?

Robot turns with no velocity commands

Hi all!,
I've just download the package and install it at the instructions. I compile it and everything is perfect.

But when I launch the simulation (with just one Summit, I have no test with more) it starts to turn counterclockwise without given to it any cmd_vel.

Here are 2 videos were you can appreciate it.

Video1 and video2.

How can I solve it?

I'm on Ubuntu 16.04 and I have update Gazebo to 7.14

Thank you,
Jorge

How to move the robot with torques?

Hello, I have recently started working on a project with a Summit-X vehicle. We would like to control the robot with torque controls on the wheels. I understand how to send velocity commands to the wheels, but we would like to have control over the torques.

Is there a specific rostopic that I need to publish on in order to achieve torque control? I have tried to locate it, but I am at a loss. If anyone can show me how to move the robot using torque controls instead of velocity controls it would be much appreciated.

Summit XL steel errors during launch

Hello,

I am trying to launch the Summit XL Steel simulation on gazebo with navigation using the instructions mentioned.
I use the command roslaunch summit_xl_sim_bringup summit_xls_complete.launch
But, I get several errors.

I found a similar issue reported in the issue 15, but the solution mentioned there doesn't seem to work. I am not able to find the yaml file mentioned in the solution to the above issue to make the recommended changes.
Maybe I am looking at it wrong or something I am doing is not right.

Any help is much appreciated.
Below are the details of the error:

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

setting /run_id to 46c8328c-157b-11eb-9fa6-38d547ac34e2
process[rosout-1]: started with pid [30233]
started core service [/rosout]
process[robot/robot_state_publisher-2]: started with pid [30250]
process[robot/urdf_spawner_summit_model-3]: started with pid [30251]
process[robot/controller_spawner-4]: started with pid [30252]
process[robot/twist_mux-5]: started with pid [30266]
process[robot/twist_marker-6]: started with pid [30279]
process[robot/map_server-7]: started with pid [30302]
process[robot/amcl-8]: started with pid [30319]
process[robot/move_base-9]: started with pid [30335]
process[gazebo-10]: started with pid [30353]
process[gazebo_gui-11]: started with pid [30374]
process[rviz-12]: started with pid [30399]
[ INFO] [1603490479.342321554]: Requesting the map...
[ WARN] [1603490479.343292877]: Request for map failed; trying again...
[INFO] [1603490479.449792, 0.000000]: Controller Spawner: Waiting for service controller_manager/load_controller
[ INFO] [1603490479.498800089]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1603490479.499196423]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1603490479.526290060]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1603490479.526605334]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
SpawnModel script started
[INFO] [1603490479.702561, 0.000000]: Loading model XML from ros parameter
[INFO] [1603490479.705242, 0.000000]: Waiting for service /gazebo/spawn_urdf_model
[ INFO] [1603490481.364996771]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1603490481.369622917]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1603490481.410089662]: Physics dynamic reconfigure ready.
[ INFO] [1603490481.412015584]: Physics dynamic reconfigure ready.
[INFO] [1603490481.512005, 0.015000]: Calling service /gazebo/spawn_urdf_model
[ INFO] [1603490481.760212792, 0.045000000]: Camera Plugin: Using the 'robotNamespace' param: '/robot/'
[ INFO] [1603490481.762364905, 0.045000000]: Camera Plugin (ns = /robot/)  <tf_prefix_>, set to "/robot"
[ INFO] [1603490481.762499236, 0.045000000]: <robotNamespace> set to: /robot//
[ INFO] [1603490481.762519836, 0.045000000]: <topicName> set to: /robot//imu/data
[ INFO] [1603490481.762531246, 0.045000000]: <frameName> set to: robot_imu_link
[ INFO] [1603490481.762553553, 0.045000000]: <updateRateHZ> set to: 100
[ INFO] [1603490481.762575037, 0.045000000]: <gaussianNoise> set to: 0
[ INFO] [1603490481.762597928, 0.045000000]: <xyzOffset> set to: 0 0 0
[ INFO] [1603490481.762636063, 0.045000000]: <rpyOffset> set to: 0 -0 0
Master Unknown message type[subscr] From[55696]
[ INFO] [1603490481.804065109, 0.045000000]: Laser Plugin: Using the 'robotNamespace' param: '/robot/'
[ INFO] [1603490481.804107555, 0.045000000]: Starting GazeboRosLaser Plugin (ns = /robot/)
[ INFO] [1603490481.804680242, 0.045000000]: GPU Laser Plugin (ns = /robot/) <tf_prefix_>, set to "/robot"
[ INFO] [1603490481.805603361, 0.045000000]: LoadThread function completed
[ INFO] [1603490481.810759706, 0.045000000]: Laser Plugin: Using the 'robotNamespace' param: '/robot/'
[ INFO] [1603490481.810795577, 0.045000000]: Starting GazeboRosLaser Plugin (ns = /robot/)
[INFO] [1603490481.811535, 0.045000]: Spawn status: SpawnModel: Successfully spawned entity
[ INFO] [1603490481.811608637, 0.045000000]: GPU Laser Plugin (ns = /robot/) <tf_prefix_>, set to "/robot"
[ INFO] [1603490481.812477451, 0.045000000]: LoadThread function completed
[ INFO] [1603490481.830590145, 0.045000000]: Loading gazebo_ros_control plugin
[ INFO] [1603490481.830688833, 0.045000000]: Starting gazebo_ros_control plugin in namespace: /robot/
[ INFO] [1603490481.831207345, 0.045000000]: gazebo_ros_control plugin is waiting for model URDF in parameter [/robot/robot_description] on the ROS param server.
[ERROR] [1603490481.939565724, 0.045000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/robot_front_right_wheel_joint
[ERROR] [1603490481.940310173, 0.045000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/robot_front_left_wheel_joint
[ERROR] [1603490481.941003047, 0.045000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/robot_back_left_wheel_joint
[ERROR] [1603490481.941637360, 0.045000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/robot_back_right_wheel_joint
[ERROR] [1603490481.942262808, 0.045000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/robot_front_laser_base_joint
[ERROR] [1603490481.942881154, 0.045000000]: No p gain specified for pid.  Namespace: /gazebo_ros_control/pid_gains/robot_rear_laser_base_joint
[ INFO] [1603490481.946871339, 0.045000000]: Loaded gazebo_ros_control.
[ INFO] [1603490481.949864129, 0.045000000]: PlanarMovePlugin missing <enableYAxis>, defaults to "1"
[robot/urdf_spawner_summit_model-3] process has finished cleanly
log file: /home/akilesh/.ros/log/46c8328c-157b-11eb-9fa6-38d547ac34e2/robot-urdf_spawner_summit_model-3*.log
[INFO] [1603490482.159622, 0.245000]: Controller Spawner: Waiting for service controller_manager/switch_controller
[INFO] [1603490482.160716, 0.246000]: Controller Spawner: Waiting for service controller_manager/unload_controller
[INFO] [1603490482.161719, 0.248000]: Loading controller: joint_read_state_controller
[INFO] [1603490482.166706, 0.253000]: Loading controller: joint_pan_position_controller
[ERROR] [1603490482.192840388, 0.277000000]: Exception thrown while initializing controller joint_pan_position_controller.
Could not find resource 'robot_front_ptz_camera_pan_joint' in 'hardware_interface::VelocityJointInterface'.
[ERROR] [1603490482.192915822, 0.277000000]: Initializing controller 'joint_pan_position_controller' failed
[ INFO] [1603490482.503542397, 0.588000000]: Received a 4992 X 4992 map @ 0.020 m/pix

[ INFO] [1603490482.923518542, 1.008000000]: Initializing likelihood field model; this can take some time on large maps...
[ERROR] [1603490483.199025, 1.283000]: Failed to load joint_pan_position_controller
[INFO] [1603490483.199284, 1.283000]: Loading controller: joint_tilt_position_controller
[ERROR] [1603490483.224110538, 1.308000000]: Exception thrown while initializing controller joint_tilt_position_controller.
Could not find resource 'robot_front_ptz_camera_tilt_joint' in 'hardware_interface::VelocityJointInterface'.
[ERROR] [1603490483.224146760, 1.308000000]: Initializing controller 'joint_tilt_position_controller' failed
[ERROR] [1603490484.228260, 2.311000]: Failed to load joint_tilt_position_controller
[INFO] [1603490484.228565, 2.312000]: Controller Spawner: Loaded controllers: joint_read_state_controller
[INFO] [1603490484.230355, 2.314000]: Started controllers: joint_read_state_controller
[ INFO] [1603490484.766970476, 2.850000000]: Done initializing likelihood field model.

pid_gains not defined

After downloading and installing all the dependencies for the simulator, I get the following error message when starting the sim.

[ERROR] [1568037865.296948751, 0.001000000]: No p gain specified for pid. Namespace: /summit_xl_a/gazebo_ros_control/pid_gains/summit_xl_a_front_right_wheel_joint [ERROR] [1568037865.297741982, 0.001000000]: No p gain specified for pid. Namespace: /summit_xl_a/gazebo_ros_control/pid_gains/summit_xl_a_front_left_wheel_joint [ERROR] [1568037865.298591089, 0.001000000]: No p gain specified for pid. Namespace: /summit_xl_a/gazebo_ros_control/pid_gains/summit_xl_a_back_left_wheel_joint [ERROR] [1568037865.299297377, 0.001000000]: No p gain specified for pid. Namespace: /summit_xl_a/gazebo_ros_control/pid_gains/summit_xl_a_back_right_wheel_joint [ERROR] [1568037865.301091322, 0.001000000]: No p gain specified for pid. Namespace: /summit_xl_a/gazebo_ros_control/pid_gains/summit_xl_a_front_ptz_camera_pan_joint [ERROR] [1568037865.302231992, 0.001000000]: No p gain specified for pid. Namespace: /summit_xl_a/gazebo_ros_control/pid_gains/summit_xl_a_front_ptz_camera_tilt_joint
How can I fix this error? I believe it is responsible for the erratic behavior I'm seeing when trying to control the summit_xl with a gamepad. Thank you.

If it matters, I am using ROS Melodic on Ubuntu 18.04.

an issue in summit_xls simulation: missing odom and map frames, no map received for local costmap

Hello,

I wanted to bring to your attention an issue I encountered with the summit_xls simulation in melodic after migrating from kinetic.

  1. I have noticed that the rqt_tf_tree does not display the odom frame (summit_xl_a_odom) and map frame (summit_xl_a_map) in the simulation. I am unsure which node or package in summit_xl_sim is responsible for publishing the odom topic, as the base_hw package handles the physical robot's odom publication. Could you please guide me on which node, source code, or configuration I should review to address this issue?

  2. To address the above problem, I added an external package, which has helped to display the odom and map frames in the rqt_tf_tree. However, I have encountered another issue with the local costmap, which is not receiving any map data and is displaying a warning message that reads "no map received for local costmap". Since the global costmap is functioning correctly, I suspect that the costmap converter is working correctly.

Any assistance would be really appreciative. Thank you for your anticipated assistance.

JW

Output odom response does not match the step input

We are trying to move the SUMMIT XL in a straight line in gazebo. The differential drive plugin for wheel joints is enabled and we gave a step input velocity to robot and observed the output response from \odom topic.
There are sudden dips/ falls in the output responses for a small period of time. The output response and step input are shown below:
image
Ideally, both the input and outputs must match, as we do the robot motion in a ideal simulation environment. Can anyone clarify why this discrepancy pops up?

The real-time angular velocity obtained by summit xl steel in the simulation is not consistent with the speed we released.

When the angular velocity of the robot is sent to the robot 1rad/s in the form of rostopic pub, the robot in the simulation does not reach the angular velocity we sent it. Looking at the odom, it is found that the angular velocity is 0.781rad/s. What is the reason for this?

The command he runs is:
roslaunch summit_xl_sim_bringup summit_xls_complete.launch

and the Gazebo world is launched with use_sim_time = true

Gazebo- Front wheels of SUMMIT XL yields erratic motion (lifting upwards) when trying to move in straight line.

The objective is to rotate the wheels as the robot moves on in a straight line. To this end, we enabled the robotnik_base_control in simulation environment to control and rotate the wheels and tried to replicate the real-world motion of robot.
However, on doing that, the robot outputs an erratic behaviour, wherein it skids and the front wheel is lifted upwards as the robot moves on.
image

Any help on this issue is appreciated...

ERROR-SUMMIT XL- roslaunch summit_xl_sim_bringup summit_xl_complete.launch

I have this error !!. Please help!!
Ubuntu 14.04 LTS
ROS-Indigo

ROS@ubuntu:~/summit_ws$ roslaunch summit_xl_sim_bringup summit_xl_complete.launch
... logging to /home/andy/.ros/log/ee0a06e6-a3e2-11e7-b353-a0f3c12449d2/roslaunch-ubuntu-12412.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.

Traceback (most recent call last):
File "/opt/ros/indigo/share/xacro/xacro.py", line 62, in
xacro.main()
File "/opt/ros/indigo/lib/python2.7/dist-packages/xacro/init.py", line 696, in main
eval_self_contained(doc)
File "/opt/ros/indigo/lib/python2.7/dist-packages/xacro/init.py", line 626, in eval_self_contained
eval_all(doc.documentElement, macros, symbols)
File "/opt/ros/indigo/lib/python2.7/dist-packages/xacro/init.py", line 526, in eval_all
(str(name), str(node.tagName)))
xacro.XacroException: Invalid parameter "name" while expanding macro "xacro:sensor_hokuyo_urg04lx"
while processing /home/andy/summit_ws/src/summit_xl_sim/summit_xl_gazebo/launch/summit_xl.launch:
Invalid tag: Cannot load command parameter [robot_description]: command [/opt/ros/indigo/share/xacro/xacro.py '/home/andy/summit_ws/src/summit_xl_common/summit_xl_description/robots/summit_xl.urdf.xacro'] returned with code [1].

Param xml is
The traceback for the exception was written to the log file

ImportError: dynamic module does not define module export function (PyInit__tf2)

I am trying to launch the simulation in gazebo. The compilation phase went well but during launch I keep getting the following error

ImportError: dynamic module does not define module export function (PyInit__tf2)

And here is the complete output. Kindly let me know if any solution is available thanks.

Traceback (most recent call last):
File "/opt/ros/kinetic/lib/gazebo_ros/spawn_model", line 32, in
import tf.transformations as tft
File "/opt/ros/kinetic/lib/python2.7/dist-packages/tf/init.py", line 28, in
from tf2_ros import TransformException as Exception, ConnectivityException, LookupException, ExtrapolationException
File "/opt/ros/kinetic/lib/python2.7/dist-packages/tf2_ros/init.py", line 38, in
from tf2_py import *
File "/opt/ros/kinetic/lib/python2.7/dist-packages/tf2_py/init.py", line 38, in
from ._tf2 import *
ImportError: dynamic module does not define module export function (PyInit__tf2)
[ INFO] [1564547659.199729206]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1564547659.200105700]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1564547659.221360613]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1564547659.221721097]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[INFO] [1564547659.228035, 0.000000]: Controller Spawner: Waiting for service controller_manager/load_controller
[summit_xl_a/urdf_spawner_summit_model-3] process has died [pid 11002, exit code 1, cmd /opt/ros/kinetic/lib/gazebo_ros/spawn_model -x 0 -y 0 -z 0 -urdf -param robot_description -model summit_xl_a __name:=urdf_spawner_summit_model __log:=/home/zain/.ros/log/754550aa-b34c-11e9-9cce-5c5f678de2bc/summit_xl_a-urdf_spawner_summit_model-3.log].
log file: /home/zain/.ros/log/754550aa-b34c-11e9-9cce-5c5f678de2bc/summit_xl_a-urdf_spawner_summit_model-3*.log
[ INFO] [1564547660.198802804, 0.022000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1564547660.227512636, 0.050000000]: Physics dynamic reconfigure ready.
[ INFO] [1564547660.286905771, 0.107000000]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1564547660.320738700, 0.140000000]: Physics dynamic reconfigure ready.
^C[rviz-9] killing on exit
[gazebo_gui-8] killing on exit
[gazebo-7] killing on exit
[summit_xl_a/twist_marker-6] killing on exit
[summit_xl_a/twist_mux-5] killing on exit
[summit_xl_a/controller_spawner-4] killing on exit
[summit_xl_a/robot_state_publisher-2] killing on exit
[WARN] [1564547669.847412, 9.022000]: Controller Spawner couldn't find the expected controller_manager ROS interface.
[rosout-1] killing on exit
[master] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete

Summit XL errors during launch and planting

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

  • /axis_angular: 2
  • /axis_linear_x: 1
  • /axis_linear_y: 0
  • /axis_linear_z: 3
  • /button_dead_man: 11
  • /button_home: 8
  • /button_kinematic_mode: 9
  • /button_output_1: 15
  • /button_output_2: 13
  • /button_ptz_pan_left: 7
  • /button_ptz_pan_right: 5
  • /button_ptz_tilt_down: 6
  • /button_ptz_tilt_up: 4
  • /button_ptz_zoom_tele: 0
  • /button_ptz_zoom_wide: 3
  • /button_speed_down: 14
  • /button_speed_up: 12
  • /cmd_service_home: /summit_xl_contro...
  • /cmd_service_io: /modbus_io/write_...
  • /cmd_service_set_mode: /summit_xl_contro...
  • /cmd_topic_ptz: /axis_camera/ptz_...
  • /cmd_topic_vel: /pad_teleop/cmd_vel
  • /joystick_dead_zone: true
  • /num_of_buttons: 15
  • /output_1: 1
  • /output_2: 2
  • /pan_increment: 5
  • /ps3_joy/autorepeat_rate: 10.0
  • /ps3_joy/deadzone: 0.12
  • /ps3_joy/dev: /dev/input/js0
  • /robot_description: <?xml version="1....
  • /rosdistro: kinetic
  • /rosversion: 1.12.7
  • /scale_angular: 1.5
  • /scale_linear: 1.5
  • /scale_linear_z: 20.0
  • /summit_xl/joint_blw_velocity_controller/joint: joint_back_left_w...
  • /summit_xl/joint_blw_velocity_controller/pid/d: 10.0
  • /summit_xl/joint_blw_velocity_controller/pid/i: 0.01
  • /summit_xl/joint_blw_velocity_controller/pid/p: 100.0
  • /summit_xl/joint_blw_velocity_controller/type: effort_controller...
  • /summit_xl/joint_brw_velocity_controller/joint: joint_back_right_...
  • /summit_xl/joint_brw_velocity_controller/pid/d: 10.0
  • /summit_xl/joint_brw_velocity_controller/pid/i: 0.01
  • /summit_xl/joint_brw_velocity_controller/pid/p: 100.0
  • /summit_xl/joint_brw_velocity_controller/type: effort_controller...
  • /summit_xl/joint_flw_velocity_controller/joint: joint_front_left_...
  • /summit_xl/joint_flw_velocity_controller/pid/d: 10.0
  • /summit_xl/joint_flw_velocity_controller/pid/i: 0.01
  • /summit_xl/joint_flw_velocity_controller/pid/p: 100.0
  • /summit_xl/joint_flw_velocity_controller/type: effort_controller...
  • /summit_xl/joint_frw_velocity_controller/joint: joint_front_right...
  • /summit_xl/joint_frw_velocity_controller/pid/d: 10.0
  • /summit_xl/joint_frw_velocity_controller/pid/i: 0.01
  • /summit_xl/joint_frw_velocity_controller/pid/p: 100.0
  • /summit_xl/joint_frw_velocity_controller/type: effort_controller...
  • /summit_xl/joint_pan_position_controller/joint: joint_camera_pan
  • /summit_xl/joint_pan_position_controller/pid/d: 50.0
  • /summit_xl/joint_pan_position_controller/pid/i: 0.01
  • /summit_xl/joint_pan_position_controller/pid/p: 100.0
  • /summit_xl/joint_pan_position_controller/type: effort_controller...
  • /summit_xl/joint_read_state_controller/publish_rate: 100.0
  • /summit_xl/joint_read_state_controller/type: joint_state_contr...
  • /summit_xl/joint_tilt_position_controller/joint: joint_camera_tilt
  • /summit_xl/joint_tilt_position_controller/pid/d: 50.0
  • /summit_xl/joint_tilt_position_controller/pid/i: 0.01
  • /summit_xl/joint_tilt_position_controller/pid/p: 100.0
  • /summit_xl/joint_tilt_position_controller/type: effort_controller...
  • /summit_xl_robot_control/blw_pos_topic: /summit_xl/joint_...
  • /summit_xl_robot_control/blw_vel_topic: /summit_xl/joint_...
  • /summit_xl_robot_control/brw_pos_topic: /summit_xl/joint_...
  • /summit_xl_robot_control/brw_vel_topic: /summit_xl/joint_...
  • /summit_xl_robot_control/flw_pos_topic: /summit_xl/joint_...
  • /summit_xl_robot_control/flw_vel_topic: /summit_xl/joint_...
  • /summit_xl_robot_control/frw_pos_topic: /summit_xl/joint_...
  • /summit_xl_robot_control/frw_vel_topic: /summit_xl/joint_...
  • /summit_xl_robot_control/joint_back_left_wheel: joint_back_left_w...
  • /summit_xl_robot_control/joint_back_right_wheel: joint_back_right_...
  • /summit_xl_robot_control/joint_blw_steer: joint_back_left_s...
  • /summit_xl_robot_control/joint_brw_steer: joint_back_right_...
  • /summit_xl_robot_control/joint_flw_steer: joint_front_left_...
  • /summit_xl_robot_control/joint_front_left_wheel: joint_front_left_...
  • /summit_xl_robot_control/joint_front_right_wheel: joint_front_right...
  • /summit_xl_robot_control/joint_frw_steer: joint_front_right...
  • /summit_xl_robot_control/model: summit_xl
  • /summit_xl_robot_control/publish_odom_tf: False
  • /summit_xl_robot_control/summit_xl_d_tracks_m: 1.0
  • /summit_xl_robot_control/summit_xl_wheel_diameter: 0.25
  • /tilt_increment: 5
  • /twist_mux/locks: [{'topic': 'e_sto...
  • /twist_mux/topics: [{'topic': 'pad_t...
  • /use_sim_time: True
  • /zoom_increment: 300

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 : summit_xl
[ INFO] [1493892061.215892612]: Opened joystick: /dev/input/js0. deadzone_: 0.120000.
[ INFO] [1493892061.224011217]: summit_xl_wheel_diameter_ = 0.25
[ INFO] [1493892061.224059378]: summit_xl_d_tracks_m_ = 1.00
[ INFO] [1493892061.226181772]: NOT PUBLISHING odom->base_footprint tf
[ INFO] [1493892061.277524508]: SummitXLPad num_of_buttons_ = 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
[ INFO] [1493892061.284097942]: summit_xl_robot_control::spin()
[ INFO] [1493892061.284146066]: SummitXLControllerClass::starting
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.284273740, 0.360000000]: SummitXLControllerClass::starting
[ 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 = /) <tf_prefix_>, 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 <covariance_x>, defaults to 0.000100
[ WARN] [1493892062.611416739, 0.360000000]: GazeboRosSkidSteerDrive Plugin (ns = /summit_xl/) missing <covariance_y>, defaults to 0.000100
[ WARN] [1493892062.611431970, 0.360000000]: GazeboRosSkidSteerDrive Plugin (ns = /summit_xl/) missing <covariance_yaw>, 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
[ INFO] [1493892063.284466023, 0.954000000]: SummitXLControllerClass::starting
[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_state_controller
[ INFO] [1493892065.284760983, 2.947000000]: SummitXLControllerClass::starting

I don't understand why my gazebo is constantly dying.

Thank you for helping me please.

Summit XL does not move in the desired path in Gazebo.

We are trying to move the summit xl in circular path in gazebo. However, the robot does not move in the desired path in gazebo; contrarily rviz shows that circular motion is achieved. The following gif files shows the inputs and outputs for this motion:
Input: Linear velocity and radius

Output:
image

We presume that the differential drive plugin of summit xl is not configured properly in gazebo.
Any help on this issue would be appreciated. Thank you
Link to gif file: https://lh3.googleusercontent.com/-CcvBoE5k4Q4/XuCFzD51-HI/AAAAAAAAAyY/qx6PJK7ddeoefovxrRAWztAZPb7iiOzxACK8BGAsYHg/s0/2020-06-10.gif

Error docker installation

Hello I already have docker, nvidia-docker, and nvidia driver installed but when I execute the docker/simulation-in-container-run.sh, it show the next error:

[INFO]: Checking tools [SUCCESS]: All required tools are available [INFO]: Checking display [SUCCESS]: Display found [INFO]: Checking Nvidia CUDA [SUCCESS]: Nvidia CUDA version 11.7 ERROR]: Couldn find a suitable testing image of nvidia docker

I dont know if i need another version of the docker, I am new with the docker cointainers.

Software version:
Ubuntu 20.04
docker 20.10.21
nvidia docker: nvidia/cuda 11.6.2

LaserScan-Topic just shows INF using Gazebo

When I start the Gazebo Simulation (like supposed in the ReadMe-File) using

$ roslaunch summit_xl_sim_bringup summit_xl_complete.launch move_base_robot_a:=true amcl_and_mapserver_a:=true localization_robot_a:=true

the LaserScanners (front and rear) just show -inf. So the navigation does not work.

$ rostopic echo /robot/front_laser/scan

header: 
  seq: 16281
  stamp: 
    secs: 316
    nsecs: 328000000
  frame_id: "robot_front_laser_link"
angle_min: -2.35619997978
angle_max: 2.35619997978
angle_increment: 0.00436333334073
time_increment: 0.0
scan_time: 0.0
range_min: 0.0599999986589
range_max: 10.0
ranges: [-inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, -inf, 

The Gazebo-Summit is not moved and should see the walls within 4..5m.
Nothing is edited in the clone of this repository using ROS-melodic with Gazebo 9.

Do I just have to reconfigure something?
Is this a Gazebo-Problem?
Do I have to use ROS-Kinetic?
Any help would be appreciated.

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.