The spawn_urdf_model
service just creates a model in Gazebo. It won't create any of the nodes you need to control it, as that is functionality outside of Gazebo. You will need to launch the nodes that control the simulated robot as well if you want to control it like a real robot.
If your goal is just to make the quadrotor move around and behave as an obstacle for your robot, then you can use the set_model_state
and related services to make models move around.
If your goal is to have a simulated quadrotor that you can control from ROS, then you will need to do something more complex. One option is to use make a system command call to start roslaunch
with a launch file that either creates the quadrotor and related nodes, or stops a running launch. This would work but I think it would be messy and hard to manage - you would need to keep track of PIDs and watch the roslaunch output to look for errors. If you were using Python this would be relatively easy using the subprocess
package. I think that Poco provides something similar for C++ but I've never used it.
Another option is a package called rosspawn, which is intended to provide a ROS API for launching ROS nodes. It hasn't been updated since Electric, though, so it probably would require some work to make it usable.
Finally, you could try editing the nodes that control the quadcopters to support dynamic_reconfigure, have the controller nodes always running, and dynamically reconfigure them to point them at new Gazebo models when you spawn them.
Edit: Having just seen one of your many other questions, I've found out that the Hector quadrotor can use Gazebo controllers in simulation, which should provide the topics you need. So if you use the spawn_sdf
model service and load the Gazebo simulation file, not just the URDF, then it should load all the control plugins for you as well.
Another edit:
I spent some time working with the hector_* packages, and I've managed to get a handle on how the simulation part is set up.
All the controllers that you want are implemented as ros_control controllers. This means that they work with the Gazebo ros_control support. The great thing about this for you is that you can call the spawn_sdf_model
service and pass the contents of the quadrotor.gazebo
file (which you need to generate by passing hector_quadrotor_description/urdf/quadrotor.gazebo
to xacro) to spawn a new instance of the quadrotor model, ready to go. To start the controllers, all you need to do then is call the controller_manager/load_controller
service. The name of the controller that subscribes to the /cmd_vel
topic is controller/twist
. From the command line, this looks like:
rosservice call /controller_manager/load_controller controller/twist
Do something similar from C++ by making a service client for that service and calling it with controller/twist
as the name of the controller to load.
So to sum up, this will be two service calls to spawn a new quadrotor and start its controller. One call to Gazebo's spawn_sdf_model
service and one call to /controller_manager/load_controller
.
However, you will need to provide a bunch of parameters to allow the controller to work properly. Below is a cut-down launch file that I was using for testing. It loads all the necessary parameters. It may also load some unnecessary ones; experimentation will tell you which are necessary. The most important part is the loading of controller.yaml
, which configures the controller's PID values, etc.
<?xml version="1.0"?>
<launch>
<include file="$(find gazebo_ros)/launch/empty_world.launch"/>
<!-- send the robot XML to param server -->
<param name="robot_description" command="$(find xacro)/xacro '$(find hector_quadrotor_description)/urdf/quadrotor.gazebo.xacro' base_link_frame:=base_link world_frame:=world" />
<param name="tf_prefix" type="string" value="" />
<param name="base_link_frame" type="string" value="/base_link"/>
<param name="world_frame" type="string" value="world"/>
<!-- push robot_description to factory and spawn robot in gazebo -->
<node name="spawn_robot" pkg="gazebo_ros" type="spawn_model"
args="-param robot_description -urdf -model quadrotor"
respawn="false" output="screen"/>
<arg name="motors" default="robbe_2827-34_epp1045" />
<rosparam command="load" file="$(find hector_quadrotor_model)/param/quadrotor_aerodynamics.yaml" />
<rosparam command="load" file="$(find hector_quadrotor_model)/param/$(arg motors).yaml" />
<!-- spawn controller -->
<param name="controller/state_topic" value="state" />
<param name="controller/imu_topic" value="imu" />
<rosparam file="$(find hector_quadrotor_controller)/params/controller.yaml" />
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false" output="screen" args="controller/twist --shutdown-timeout 3"/>
</launch>
When you want to delete the model, don't forget to also shut down its controller using controller_manager/unload_controller
.
Originally posted by Geoff with karma: 4203 on 2017-04-23
This answer was ACCEPTED on the original site
Post score: 2
Original comments
Comment by [email protected] on 2017-04-24:
Hi Geoff
It sounds like the last suggestion is really promising for me. But I am not sure whether I am right or not. Originally, quadrotor is descripted by a .xacro file. And in .launch file, except for the model, some control node also spawned. I think this is why I cannot call cmd_vel.
Comment by [email protected] on 2017-04-24:
But, as you suggested, I can transfer a .launch file to a sdf file so that every control node will be included in the spawned model. Am I right about it? Because, I must use c++ to spawn a robot and the spawned robot should have exactly the same capability as initial launched robot.
Comment by [email protected] on 2017-04-24:
So I am wondering whether there are some ways to launch a .launch file in c++. Do you have some ideas towards this? I am grateful for any reply from you.
Comment by [email protected] on 2017-04-24:
Or, do you know some ways to run multiple (maybe hundreds) simulations together? Because the aim for respawning robots is for reseting the experiments so that in on simulation actually I can run multiple simulation subsequently. Do you know some ways to realize this? Thank you very much
Comment by Geoff on 2017-04-24:
You cannot copy nodes from a launch file to an sdf file. Gazebo SDF has nothing to do with ROS nodes. Gazebo does support controller plugins, but these are separate from ROS nodes which may provide other controllers.
Comment by [email protected] on 2017-04-24:
I think .urdf can do the similar thing. My urdf file is parsed from a .xacro file. I remember in that urdf file I see some plugin tags. But in my launch file, except for the model, it also include nodes for control stuff, such as ground_to_truth.
Comment by [email protected] on 2017-04-24:
Excuse me sir, now I have .xacro file for descripting the hector_quadrotor and .launch file for spawning a hector quadrotor with all necessary control plugins. Do you know how to only use c++ code to spawn a real hector quadrotor robot that can be controlled. This is very important to me.
Thanks
Comment by Geoff on 2017-04-24:
Technically, URDF cannot do a similar thing, but it can contain the information used by Gazebo because most tools that use URDF will ignore the tags they don't understand. This makes it easy to put things like Gazebo plugins in the URDF and use a single file, which is convenient.
Comment by [email protected] on 2017-04-24:
So, is there tutorials or examples that show to how to transform all stuff I need to a sdf file? Thanks.
Comment by Geoff on 2017-04-24:
You don't need to. The Hector Quadrotor stuff already comes with an SDF file, quadrotor.gazebo.xacro
. It's just that it's an xacro template, so you need to pass it to xacro before using it. The parameters, you can put in your launch file.
Comment by [email protected] on 2017-04-25:
Yes, I understand it. But in my simulation, under some conditions, each robot will remove from the space. When all robots are removed, the simulation terminate. But, based on my project, I need to run more than 1000 simulations.
Comment by [email protected] on 2017-04-25:
So, I planned to respawn all removed robots and put them in original position. By this way, in one simulation I can always remove robots, then reset it so that in one simulation actually I can run multiple simulations
Comment by [email protected] on 2017-04-25:
The algorithm for robot is controlled by a c++ file as external node. All spawn and remove must happed there. That is why repawning a robot must fully happen there. Do you have some idea towards it, Sir?
Comment by Geoff on 2017-04-25:
I have told you how to do it fully from C++. Gazebo terminating after deleting a model is probably a bug, and you should post a separate question about that with the complete error output and source that can be used to reproduce the error.
Comment by [email protected] on 2017-04-25:
Actually I already solve the problem of the code above. My new problem is I can spawn a quadrotor during the simulation. But, that is just a mode. I cannot call topic service in c++ to move it. So, I am wondering how to spawn a really contollable quadrotor in c++
Comment by Geoff on 2017-04-25:
Using the stuff I discussed in my answer, I was able to spawn a quadrotor in the simulation, move it using the /cmd_vel topic, and then delete it. What topics or services do you want to call that are not present?
Comment by [email protected] on 2017-07-10:
Hi Geoff, could you tell me how to convert quadrotor.gazebo.xacro to .sdf file that I can use in spawn_sdf_model service? Thanks
Comment by Geoff on 2017-07-10:
Run it through xacro, like this:
rosrun xacro xacro quadrotor.gazebo.xacro > quadrotor.gazebo.sdf
By the way, if the above answer solves your problem please mark it as accepted, so that others who have the same problem know how to fix it.
Comment by [email protected] on 2017-07-10:
Hi Geoff, I meet with some issues for spawning a hector_quadrotor with spawn_sdf_model service. I think may I did not generate the right .sdf file. I use spawn_sdf_model service just for spawning a model without calling controlling service. But gazebo crashed. I do not know why.
Comment by [email protected] on 2017-07-10:
By using the same code. I downloaded a .sdf file from the website and tried it. It works. Is that I need to set parameters in C++ for .sdf file before I generate the model? Or some other reasons?
Comment by Geoff on 2017-07-10:
Which SDF file did you download?
Comment by [email protected] on 2017-07-10:
A very easy sdf file that just creates a box in the space. I downloaded it from ROS tutorial website. this is the link: http://gazebosim.org/tutorials?tut=build_model. In my code, I only try to create a model from the file that is converted from .xacro to .sdf. Should I specify something more in C++
Comment by [email protected] on 2017-07-10:
Hi Geoff. Do you have time for having a look at my code? If you can, could you share your email with me so that I can send you the file. In comment field, I cannot include many characters. Thank you very much.
Comment by [email protected] on 2017-07-11:
Hello, Geoff. Just now, I found actually I can call spawn_urdf_model service to create a model with topics for it by including plugins in the .urdf file. But it seems like I need to specify parameters for each .so file. Do you know how to add cmd_vel and ground_to_truth/pose topic through this way.
Comment by Geoff on 2017-07-11:
Look at the last part of my answer. It's setting some of those parameters in the launch file. If you want to set them at runtime, you can use the parameter server API to do so. See this tutorial for how to do that.
Comment by [email protected] on 2017-07-11:
Thank you very much Geoff, I will try to handle them by myself.
Comment by [email protected] on 2017-07-11:
Hi geoff. Does it mean I must set parameters value in C++ for every spawning of new robot?
Comment by [email protected] on 2017-07-11:
Excuse me Geoff. Could you share your quadrotor.gazebo.sdf file with me? I still cannot solve the problem with .urdf file. Sorry for bothering you.
Comment by Geoff on 2017-07-11:
If the parameters do not change, then you do not need to set the parameters for every spawning.
Comment by Geoff on 2017-07-11:
Here's the SDF file, but I would like to point out that posting the one you are having trouble with so we can fix it will be more value to you in the long run.
Comment by [email protected] on 2017-07-11:
Thanks Geoff. I will make another post for uploading my incorrect .sdf file. Thanks.