simple_launch.gazebo module
- class simple_launch.gazebo.GazeboBridge(gz_topic, ros_topic, ros_msg, direction, gz_msg=None)
Bases:
object- bidirectional = '@'
- static clock()
- generate_msg_map()
function to regenerate known messages from readme
- gz2ros = '['
- static joint_states_bridge(model)
- static model_prefix(model)
- static model_topic(model, topic)
- msg_map = {'actuator_msgs/msg/Actuators': 'gz.msgs.Actuators', 'builtin_interfaces/msg/Time': 'gz.msgs.Time', 'geometry_msgs/msg/Point': 'gz.msgs.Vector3d', 'geometry_msgs/msg/Pose': 'gz.msgs.Pose', 'geometry_msgs/msg/PoseArray': 'gz.msgs.Pose_V', 'geometry_msgs/msg/PoseStamped': 'gz.msgs.Pose', 'geometry_msgs/msg/PoseWithCovariance': 'gz.msgs.PoseWithCovariance', 'geometry_msgs/msg/PoseWithCovarianceStamped': 'gz.msgs.PoseWithCovariance', 'geometry_msgs/msg/Quaternion': 'gz.msgs.Quaternion', 'geometry_msgs/msg/Transform': 'gz.msgs.Pose', 'geometry_msgs/msg/TransformStamped': 'gz.msgs.Pose', 'geometry_msgs/msg/Twist': 'gz.msgs.Twist', 'geometry_msgs/msg/TwistStamped': 'gz.msgs.Twist', 'geometry_msgs/msg/TwistWithCovariance': 'gz.msgs.TwistWithCovariance', 'geometry_msgs/msg/TwistWithCovarianceStamped': 'gz.msgs.TwistWithCovariance', 'geometry_msgs/msg/Vector3': 'gz.msgs.Vector3d', 'geometry_msgs/msg/Wrench': 'gz.msgs.Wrench', 'geometry_msgs/msg/WrenchStamped': 'gz.msgs.Wrench', 'gps_msgs/msg/GPSFix': 'gz.msgs.NavSat', 'nav_msgs/msg/Odometry': 'gz.msgs.OdometryWithCovariance', 'rcl_interfaces/msg/ParameterValue': 'gz.msgs.Any', 'ros_gz_interfaces/msg/Altimeter': 'gz.msgs.Altimeter', 'ros_gz_interfaces/msg/Contact': 'gz.msgs.Contact', 'ros_gz_interfaces/msg/Contacts': 'gz.msgs.Contacts', 'ros_gz_interfaces/msg/Dataframe': 'gz.msgs.Dataframe', 'ros_gz_interfaces/msg/Entity': 'gz.msgs.Entity', 'ros_gz_interfaces/msg/Float32Array': 'gz.msgs.Float_V', 'ros_gz_interfaces/msg/GuiCamera': 'gz.msgs.GUICamera', 'ros_gz_interfaces/msg/JointWrench': 'gz.msgs.JointWrench', 'ros_gz_interfaces/msg/Light': 'gz.msgs.Light', 'ros_gz_interfaces/msg/ParamVec': 'gz.msgs.Param', 'ros_gz_interfaces/msg/SensorNoise': 'gz.msgs.SensorNoise', 'ros_gz_interfaces/msg/StringVec': 'gz.msgs.StringMsg_V', 'ros_gz_interfaces/msg/TrackVisual': 'gz.msgs.TrackVisual', 'ros_gz_interfaces/msg/VideoRecord': 'gz.msgs.VideoRecord', 'rosgraph_msgs/msg/Clock': 'gz.msgs.Clock', 'sensor_msgs/msg/BatteryState': 'gz.msgs.BatteryState', 'sensor_msgs/msg/CameraInfo': 'gz.msgs.CameraInfo', 'sensor_msgs/msg/FluidPressure': 'gz.msgs.FluidPressure', 'sensor_msgs/msg/Image': 'gz.msgs.Image', 'sensor_msgs/msg/Imu': 'gz.msgs.IMU', 'sensor_msgs/msg/JointState': 'gz.msgs.Model', 'sensor_msgs/msg/Joy': 'gz.msgs.Joy', 'sensor_msgs/msg/LaserScan': 'gz.msgs.LaserScan', 'sensor_msgs/msg/MagneticField': 'gz.msgs.Magnetometer', 'sensor_msgs/msg/NavSatFix': 'gz.msgs.NavSat', 'sensor_msgs/msg/PointCloud2': 'gz.msgs.PointCloudPacked', 'std_msgs/msg/Bool': 'gz.msgs.Boolean', 'std_msgs/msg/ColorRGBA': 'gz.msgs.Color', 'std_msgs/msg/Empty': 'gz.msgs.Empty', 'std_msgs/msg/Float32': 'gz.msgs.Float', 'std_msgs/msg/Float64': 'gz.msgs.Double', 'std_msgs/msg/Header': 'gz.msgs.Header', 'std_msgs/msg/Int32': 'gz.msgs.Int32', 'std_msgs/msg/String': 'gz.msgs.StringMsg', 'std_msgs/msg/UInt32': 'gz.msgs.UInt32', 'tf2_msgs/msg/TFMessage': 'gz.msgs.Pose_V', 'trajectory_msgs/msg/JointTrajectory': 'gz.msgs.JointTrajectory', 'vision_msgs/msg/Detection2D': 'gz.msgs.AnnotatedAxisAligned2DBox', 'vision_msgs/msg/Detection2DArray': 'gz.msgs.AnnotatedAxisAligned2DBox_V'}
- ros2gz = ']'
- static set_world_name(name: str)
Overwrite world name in order to avoid communicating with Gazebo Useful when Gazebo is launched in an included file, where the world name cannot be guessed
- static valid(direction)
- static world()
- yaml()
use YAML-based config for other bridges - topic_name: “chatter”
ign_topic_name: “ign_chatter” ros_type_name: “std_msgs/msg/String” ign_type_name: “ignition.msgs.StringMsg” direction: BIDIRECTIONAL # Default “BIDIRECTIONAL” - Bridge both directions
# “IGN_TO_ROS” - Bridge Ignition topic to ROS # “ROS_TO_IGN” - Bridge ROS topic
- simple_launch.gazebo.gz_launch_setup(world_file, gz_args=None)
- simple_launch.gazebo.only_show_args()
Returns True if the launch file was launched only to show its arguments
- simple_launch.gazebo.ros_gz_prefix()
- simple_launch.gazebo.silent_exec(cmd)
Executes the given command and returns the output Returns an empty list if any error