How do you add collision and physical properties to Actor model?
I am trying to simulate an environment where my bot has to interact with walking actors but the models keep walking through walls and my bot cannot detect them with sensors. How can I add collision to the Actor Model?
Below is my world sdf file being used.
<?xml version="1.0" ?>
<sdf version='1.7'>
<world name='default'>
<model name='ground_plane'>
<static>1</static>
<link name='link'>
<collision name='collision'>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<surface>
<friction>
<ode>
<mu>100</mu>
<mu2>50</mu2>
</ode>
<torsional>
<ode/>
</torsional>
</friction>
<contact>
<ode/>
</contact>
<bounce/>
</surface>
<max_contacts>10</max_contacts>
</collision>
<visual name='visual'>
<cast_shadows>0</cast_shadows>
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<script>
<uri>file://media/materials/scripts/gazebo.material</uri>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
</link>
</model>
<gravity>0 0 -9.8</gravity>
<magnetic_field>6e-06 2.3e-05 -4.2e-05</magnetic_field>
<atmosphere type='adiabatic'/>
<physics type='ode'>
<max_step_size>0.005</max_step_size>
<real_time_factor>1</real_time_factor>
<real_time_update_rate>1000</real_time_update_rate>
</physics>
<scene>
<ambient>0.4 0.4 0.4 1</ambient>
<background>0.7 0.7 0.7 1</background>
<shadows>1</shadows>
</scene>
<wind/>
<spherical_coordinates>
<surface_model>EARTH_WGS84</surface_model>
<latitude_deg>0</latitude_deg>
<longitude_deg>0</longitude_deg>
<elevation>0</elevation>
<heading_deg>0</heading_deg>
</spherical_coordinates>
<actor name="actor1">
<static>true</static>
<skin>
<filename>walk.dae</filename>
</skin>
<animation name="walking">
<filename>walk.dae</filename>
<interpolate_x>true</interpolate_x>
</animation>
<script>
<trajectory id="0" type="walking">
<waypoint>
<time>0</time>
<pose>2 2 0 0 0 -1.57</pose>
</waypoint>
<waypoint>
<time>2</time>
<pose>2 -2 0 0 0 -1.57</pose>
</waypoint>
<waypoint>
<time>2.5</time>
<pose>2 -2 0 0 0 1.57</pose>
</waypoint>
<waypoint>
<time>7</time>
<pose>2 2 0 0 0 1.57</pose>
</waypoint>
<waypoint>
<time>7.5</time>
<pose>2 2 0 0 0 -1.57</pose>
</waypoint>
</trajectory>
</script>
</actor>
</world>
</sdf>