wip: testing

This commit is contained in:
2025-04-18 11:19:26 +02:00
parent ade1f91529
commit 2b450a6d86
5 changed files with 46 additions and 38 deletions

View File

@@ -21,7 +21,7 @@
scan_line: 16 scan_line: 16
scan_rate: 10 # only need to be set for velodyne, unit: Hz, scan_rate: 10 # only need to be set for velodyne, unit: Hz,
timestamp_unit: 3 # the unit of time/t field in the PointCloud2 rostopic: 0-second, 1-milisecond, 2-microsecond, 3-nanosecond. timestamp_unit: 3 # the unit of time/t field in the PointCloud2 rostopic: 0-second, 1-milisecond, 2-microsecond, 3-nanosecond.
blind: 1.05 blind: 0.7
mapping: mapping:
acc_cov: 0.01 acc_cov: 0.01
@@ -30,7 +30,7 @@
b_gyr_cov: 0.00025 b_gyr_cov: 0.00025
fov_degree: 360.0 fov_degree: 360.0
det_range: 100.0 det_range: 100.0
extrinsic_est_en: true # true: enable the online estimation of IMU-LiDAR extrinsic, extrinsic_est_en: false # true: enable the online estimation of IMU-LiDAR extrinsic,
extrinsic_T: [ 0., 0., -0.05] extrinsic_T: [ 0., 0., -0.05]
extrinsic_R: [ 1., 0., 0., extrinsic_R: [ 1., 0., 0.,
0., 1., 0., 0., 1., 0.,

View File

@@ -46,15 +46,6 @@ def generate_launch_description():
}] }]
) )
# Load controller manager
#control_manager = Node(
# package='controller_manager',
# executable='ros2_control_node',
# parameters=[{'use_sim_time': True}, {'robot_description': '/robot_description'}],
# output='screen'
#)
# Spawner for the mecanum controller
controller = Node( controller = Node(
package='controller_manager', package='controller_manager',
executable='spawner', executable='spawner',
@@ -117,7 +108,6 @@ def generate_launch_description():
ld.add_action(gz_bridge) ld.add_action(gz_bridge)
ld.add_action(joint_state_broadcaster) ld.add_action(joint_state_broadcaster)
ld.add_action(controller) ld.add_action(controller)
#ld.add_action(control_manager)
ld.add_action(rviz2) ld.add_action(rviz2)
return ld return ld

View File

@@ -1,5 +1,5 @@
<?xml version="1.0"?> <?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" xmlns:gz="http://gazebosim.org"> <robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<material name="mecanum_wheel_material"> <material name="mecanum_wheel_material">
<ambient>0.2 0.2 0.2 1</ambient> <ambient>0.2 0.2 0.2 1</ambient>
@@ -27,16 +27,15 @@
<inertial> <inertial>
<mass value="${mass}"/> <mass value="${mass}"/>
<inertia <inertia
ixx="${0.5 * mass * radius * radius}" ixx="${(13.0/48.0) * mass * radius * radius}"
ixy="0.0" ixy="0.0"
ixz="0.0" ixz="0.0"
iyy="${0.5 * mass * radius * radius}" iyy="${0.5 * mass * radius * radius}"
iyz="0.0" iyz="0.0"
izz="${0.25 * mass * radius * radius}" izz="${(13.0/48.0) * mass * radius * radius}"
/> />
</inertial> </inertial>
<visual name='visual'> <visual name='visual'>
<pose>0 0 0 0 0 0</pose>
<geometry> <geometry>
<mesh <mesh
filename="${mesh}" filename="${mesh}"
@@ -46,27 +45,30 @@
<material name="mecanum_wheel_material"/> <material name="mecanum_wheel_material"/>
</visual> </visual>
<collision name='collision'> <collision name='collision'>
<origin xyz="0 0 0" rpy="-1.5707 0 0"/>
<geometry> <geometry>
<sphere radius="${radius}"/> <cylinder radius="${radius}" length="${radius}"/>
</geometry> </geometry>
<surface>
<friction>
<ode>
<mu>1.2</mu>
<mu2>0</mu2>
<fdir1 gz:expressed_in="${parent}_link">1 ${friction_dir} 0</fdir1>
</ode>
</friction>
</surface>
</collision> </collision>
</link> </link>
<xacro:element xacro:name="gazebo" reference="${name}_link">
<surface>
<friction>
<ode>
<mu>1.0</mu>
<mu2>0.0</mu2>
<fdir1>1 ${friction_dir} 0</fdir1>
</ode>
</friction>
</surface>
</xacro:element>
<joint name='${name}_joint' type='continuous'> <joint name='${name}_joint' type='continuous'>
<parent link="${parent}_link"/> <parent link="${parent}_link"/>
<child link="${name}_link"/> <child link="${name}_link"/>
<axis xyz="0 1 0"/> <axis xyz="0 1 0"/>
<limit <limit
velocity="5" velocity="35"
effort="100000" effort="350"
/> />
<origin xyz="${xyz}" rpy="${rpy}"/> <origin xyz="${xyz}" rpy="${rpy}"/>
</joint> </joint>

View File

@@ -27,10 +27,10 @@
<xacro:imu name="imu" parent="base" xyz="0 0 0.156" rpy="0 0 0" frequency="300"/> <xacro:imu name="imu" parent="base" xyz="0 0 0.156" rpy="0 0 0" frequency="300"/>
<xacro:ouster_lidar name="lidar" parent="base" xyz="0 0 0.15" rpy="0 0 0" model="vlp16" frequency="10" topic="/points"/> <xacro:ouster_lidar name="lidar" parent="base" xyz="0 0 0.15" rpy="0 0 0" model="vlp16" frequency="10" topic="/points"/>
<xacro:mecanum_wheel name="wheel_fr" parent="base" xyz=" 0.11 -0.11 0" rpy="0 0 0" direction="r" radius="0.04" mass="0.25"/> <xacro:mecanum_wheel name="wheel_fr" parent="base" xyz=" 0.31 -0.31 0" rpy="0 0 0" direction="r" radius="0.1" mass="10"/>
<xacro:mecanum_wheel name="wheel_fl" parent="base" xyz=" 0.11 0.11 0" rpy="0 0 0" direction="l" radius="0.04" mass="0.25"/> <xacro:mecanum_wheel name="wheel_fl" parent="base" xyz=" 0.31 0.31 0" rpy="0 0 0" direction="l" radius="0.1" mass="10"/>
<xacro:mecanum_wheel name="wheel_br" parent="base" xyz="-0.11 -0.11 0" rpy="0 0 0" direction="l" radius="0.04" mass="0.25"/> <xacro:mecanum_wheel name="wheel_br" parent="base" xyz="-0.31 -0.31 0" rpy="0 0 0" direction="l" radius="0.1" mass="10"/>
<xacro:mecanum_wheel name="wheel_bl" parent="base" xyz="-0.11 0.11 0" rpy="0 0 0" direction="r" radius="0.04" mass="0.25"/> <xacro:mecanum_wheel name="wheel_bl" parent="base" xyz="-0.31 0.31 0" rpy="0 0 0" direction="r" radius="0.1" mass="10"/>
<ros2_control name="SherpaSystem" type="system"> <ros2_control name="SherpaSystem" type="system">
<hardware> <hardware>

View File

@@ -1,6 +1,10 @@
<?xml version="1.0" ?> <?xml version="1.0" ?>
<sdf version="1.5"> <sdf version="1.5">
<world name="empty"> <world name="empty">
<physics type="ode">
<max_step_size>0.001</max_step_size>
<real_time_update_rate>100</real_time_update_rate>
</physics>
<plugin <plugin
filename="gz-sim-physics-system" filename="gz-sim-physics-system"
name="gz::sim::systems::Physics"> name="gz::sim::systems::Physics">
@@ -21,10 +25,6 @@
<plugin filename="gz-sim-imu-system" <plugin filename="gz-sim-imu-system"
name="gz::sim::systems::Imu"> name="gz::sim::systems::Imu">
</plugin> </plugin>
<plugin
filename="gz-sim-contact-system"
name="gz::sim::systems::Contact">
</plugin>
<light name="sun" type="directional"> <light name="sun" type="directional">
<pose>0 0 20 0 0 0</pose> <pose>0 0 20 0 0 0</pose>
@@ -52,10 +52,11 @@
<surface> <surface>
<friction> <friction>
<ode> <ode>
<mu>0.8</mu> <mu>50</mu>
<mu2>0.6</mu2>
</ode> </ode>
</friction> </friction>
<bounce/>
<contact/>
</surface> </surface>
</collision> </collision>
<visual name="visual"> <visual name="visual">
@@ -73,7 +74,22 @@
</script> </script>
</material> </material>
</visual> </visual>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>1</mass>
<inertia>
<ixx>1</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1</iyy>
<iyz>0</iyz>
<izz>1</izz>
</inertia>
</inertial>
</link> </link>
<pose>0 0 0 0 0 0</pose>
<self_collide>false</self_collide>
</model> </model>
</world> </world>
</sdf> </sdf>