Attaching a sensor to a PARTICULAR LINK of an animated actor
Hello, that's my first question here.
I'm currently having a really hard time trying to find out a way to connect an IMU sensor to a certain link of an animated actor. I've been experimenting a lot and now I'm posting my last piece of code below. I ended up with IMU as a big cube (just for better visualization) attached to actor's body but not to the link I wanted (RightLeg
), check out the picture.
The IMU link does not appear on the Gazebo links list in /actor1/*
list. I'm pretty sure that code's template is right but there is probably something wrong with syntax. I don't get any errors while launching the .world
file that contains following code:
<actor name="actor1">
<pose>0 1 1.25 0 0 0</pose>
<skin>
<filename>walk.dae</filename>
<scale>1.0</scale>
</skin>
<link name="imu_base">
<frame name="imu_leg">
<pose frame="actor1::RightLeg">0 0 0 0 0 0</pose>
</frame>
<pose>0 0 0 0 0 0</pose>
<visual name="imu_base_visual">
<pose>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>0.2 0.2 0.2</size> <!-- EASIER DEBUGGING -->
</box>
</geometry>
<material>
<script>
<uri>model://actor_imu/materials/actor_imu.material</uri>
<name>actor_imu/base</name>
</script>
</material>
</visual>
<sensor name="actor_imu" type="imu">
<visualize>true</visualize>
<plugin name="actor_imu" filename="libactor_imu.so"/>
<update_rate>100</update_rate> <!-- EASIER DEBUGGING -->
<always_on>1</always_on>
</sensor>
</link>
<joint name="actor1::imu_fix" type="fixed">
<parent>actor1::RightLeg</parent>
<child>imu_base</child>
</joint>
<animation name="walking">
<filename>walk.dae</filename>
<scale>1.000000</scale>
<interpolate_x>true</interpolate_x>
</animation>
<plugin name="actor1_plugin" filename="libActorPlugin.so">
<target>0 -5 1.2138</target>
<target_weight>1.15</target_weight>
<obstacle_weight>1.8</obstacle_weight>
<animation_factor>5.1</animation_factor>
<ignore_obstacles>
<model>cafe</model>
<model>ground_plane</model>
</ignore_obstacles>
</plugin>
</actor>
I checked other questions before, it is kind of related to 15389 and 14006.
Thanks in advance
EDIT:
As @chapulina
suggested, I ran gazebo
in verbose mode and this is the output:
[Wrn] [GuiIface.cc:196] g/gui-plugin is really loading a SystemPlugin. To load a GUI plugin please use --gui-client-plugin
[ INFO] [1544379941.319388836]: Finished loading Gazebo ROS API Plugin.
[ INFO] [1544379941.320842043]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[ INFO] [1544379941.391440800]: Finished loading Gazebo ROS API Plugin.
[Msg] Waiting for master.
[ INFO] [1544379941.392690107]: waitForService: Service [/gazebo/set_physics_properties] has not been advertised, waiting...
[Msg] Connected to gazebo master @ http://127.0.0.1:11345
[Msg] Publicized address: 192.168.1.156
[Err] [InsertModelWidget.cc:336] Missing model.config for model "/home/rayvburn/ped_sim_ws/src/incare_people_sim/actor_imu/materials"
[Err] [InsertModelWidget.cc:336] Missing model.config for model "/home/rayvburn/ped_sim_ws/src/incare_people_sim/actor_imu/src"
[Err] [InsertModelWidget.cc:336] Missing model.config for model "/home/rayvburn/ped_sim_ws/src/people_sim/turtlebot3_simulations/turtlebot3_gazebo/models/turtlebot3_autorace"
[ INFO] [1544379942.355888232]: waitForService: Service [/gazebo/set_physics_properties] is now available.
[ INFO] [1544379942.371552291]: waitForService: Service [/gazebo/set_physics_properties] is now available.
IMU sensor succesfully found
[ INFO] [1544379942.476708789]: Physics dynamic reconfigure ready ...
`GAZEBO_MODEL_PATH` has to be the model folder's parent dir, so you can try `export GAZEBO_MODEL_PATH=${CATKIN_WS_PATH}/src/incare_people_sim:$GAZEBO_MODEL_PATH`
Unfortunately, after change you suggested I'm still getting the same error. I think that I will get over with directly attaching IMU to an actor. Thank you very much @chapulina