ros_spawn
Functions to spawn the robots inside the Gazebo simulator.
- ros_spawn.init_robot_state_pub(namespace='/', max_pub_freq=None, launch_new_term=False) bool [source]
Funtion to initialize the robot state publisher.
- Parameters
namespace (str) – Namespace of the robot.
max_pub_freq (float) – Maximum frequency of the publisher.
launch_new_term (bool) – Launch the process in a new terminal (Xterm).
- Returns
Return true if the publisher was initialized.
- Return type
bool
- ros_spawn.spawn_model_in_gazebo(pkg_name, model_urdf_file, controllers_file, controllers_list=[], model_urdf_folder='/urdf', ns='/', args_xacro=None, max_pub_freq=None, rob_st_term=False, gazebo_name='robot1', gaz_ref_frame='world', pos_x=0.0, pos_y=0.0, pos_z=0.0, ori_w=0.0, ori_x=0.0, ori_y=0.0, ori_z=0.0)[source]
Function to spawn a model in gazebo.
- Parameters
pkg_name (str) – Package name of the model.
model_urdf_file (str) – Name of the model urdf file.
controllers_file (str) – Name of the controllers file. If None then no controllers will be loaded.
controllers_list (list) – List of the controllers to be loaded.
model_urdf_folder (str) – Folder where the model urdf file is located. Default is “/urdf”.
ns (str) – Namespace of the model. Default is “/”.
args_xacro (list) – Arguments to be passed to xacro.
max_pub_freq (float) – Maximum frequency of the robot state publisher.
rob_st_term (bool) – Launch the robot state publisher in a new terminal (Xterm).
gazebo_name (str) – Name of the gazebo model.
gaz_ref_frame (str) – Reference frame of the gazebo model.
pos_x (float) – X position of the gazebo model.
pos_y (float) – Y position of the gazebo model.
pos_z (float) – Z position of the gazebo model.
ori_w (float) – W orientation of the gazebo model.
ori_x (float) – X orientation of the gazebo model.
ori_y (float) – Y orientation of the gazebo model.
ori_z (float) – Z orientation of the gazebo model.
- Returns
Return true if the model was spawned.
- Return type
bool