updated model
This commit is contained in:
@@ -39,3 +39,15 @@
|
||||
ros_type_name: "geometry_msgs/msg/Twist"
|
||||
gz_type_name: "gz.msgs.Twist"
|
||||
direction: GZ_TO_ROS
|
||||
|
||||
- ros_topic_name: "/camera/front"
|
||||
gz_topic_name: "front_camera"
|
||||
ros_type_name: "sensor_msgs/msg/Image"
|
||||
gz_type_name: "gz.msgs.Image"
|
||||
direction: GZ_TO_ROS
|
||||
|
||||
- ros_topic_name: "/camera/camera_info"
|
||||
gz_topic_name: "camera_info"
|
||||
ros_type_name: "sensor_msgs/msg/CameraInfo"
|
||||
gz_type_name: "gz.msgs.CameraInfo"
|
||||
direction: GZ_TO_ROS
|
||||
@@ -78,9 +78,9 @@ def generate_launch_description():
|
||||
'ros2', 'run', 'ros_gz_sim', 'create',
|
||||
'-name', 'sherpa',
|
||||
'-topic', 'robot_description',
|
||||
'-x', '0', '-y', '0', '-z', '26'
|
||||
'-x', '72', '-y', '-72', '-z', '8.5'
|
||||
],
|
||||
#output='screen'
|
||||
output='screen'
|
||||
)
|
||||
|
||||
twist_stamper = Node(
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
|
||||
|
||||
<xacro:macro name="imu" params="name parent xyz rpy frequency">
|
||||
<xacro:macro name="imu" params="name parent xyz rpy frequency topic">
|
||||
|
||||
<link name="${name}_link">
|
||||
<inertial>
|
||||
@@ -27,7 +27,7 @@
|
||||
<update_rate>${frequency}</update_rate>
|
||||
<gz_frame_id>${name}_link</gz_frame_id>
|
||||
<visualize>true</visualize>
|
||||
<topic>/imu</topic>
|
||||
<topic>${topic}</topic>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
</xacro:macro>
|
||||
|
||||
@@ -141,7 +141,7 @@
|
||||
<gazebo reference="${name}_link">
|
||||
<sensor name="${name}" type="gpu_lidar">
|
||||
<update_rate>${frequency}</update_rate>
|
||||
<topic>/velodyne_points</topic>
|
||||
<topic>${topic}</topic>
|
||||
<gz_frame_id>${name}_link</gz_frame_id>
|
||||
<lidar>
|
||||
<scan>
|
||||
|
||||
@@ -77,8 +77,8 @@
|
||||
<child link="${name}_link"/>
|
||||
<axis xyz="0 1 0"/>
|
||||
<limit
|
||||
velocity="35"
|
||||
effort="350"
|
||||
velocity="5"
|
||||
effort="30"
|
||||
/>
|
||||
<origin xyz="${xyz}" rpy="${rpy}"/>
|
||||
</joint>
|
||||
|
||||
@@ -20,12 +20,14 @@
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<xacro:include filename="components/camera.xacro"/>
|
||||
<xacro:include filename="components/imu.xacro"/>
|
||||
<xacro:include filename="components/wheel.xacro"/>
|
||||
<xacro:include filename="components/ouster_lidar.xacro"/>
|
||||
|
||||
<xacro:imu name="imu" parent="base" xyz="0 0 0.35" rpy="0 0 0" frequency="300"/>
|
||||
<xacro:ouster_lidar name="lidar" parent="base" xyz="0 0 0.35" rpy="0 0 0" model="vlp16" frequency="10" topic="/points"/>
|
||||
<xacro:camera name="front_camera" parent="base" xyz="0 0 2" rpy="0 0 0" frequency="30" fov="90" topic="/front_camera"/>
|
||||
<xacro:imu name="imu" parent="base" xyz="0 0 0.35" rpy="0 0.05 0" frequency="300" topic="/imu"/>
|
||||
<xacro:ouster_lidar name="lidar" parent="base" xyz="0 0 0.35" rpy="0 0.05 0" model="vlp16" frequency="10" topic="/velodyne_points"/>
|
||||
|
||||
<link name="steer_fl_link">
|
||||
<inertial>
|
||||
|
||||
Reference in New Issue
Block a user