Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[gazebo_plugins] Rapid projector toggle rostest #419

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions gazebo_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -351,4 +351,6 @@ if (CATKIN_ENABLE_TESTING)
test/set_model_state_test/set_model_state_test.cpp)
add_rostest(test/range/range_plugin.test)
target_link_libraries(set_model_state-test ${catkin_LIBRARIES})

add_rostest(test/projector/projector.test)
endif()
Binary file added gazebo_plugins/test/projector/checker.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
16 changes: 16 additions & 0 deletions gazebo_plugins/test/projector/projector.test
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0"?>
<launch>
<arg name="gui" default="false"/>
<env name="GAZEBO_RESOURCE_PATH" value="$(find gazebo_plugins)/test/projector" />
<node name="gazebo_projector" pkg="gazebo_ros" type="gzserver"
args="$(find gazebo_plugins)/test/projector/projector.world"
output="screen"/>

<group if="$(arg gui)">
<node name="gazebo_gui" pkg="gazebo_ros" type="gzclient"
respawn="false" output="screen"/>
</group>

<test test-name="test_projector" pkg="gazebo_plugins" type="toggle.py">
</test>
</launch>
144 changes: 144 additions & 0 deletions gazebo_plugins/test/projector/projector.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,144 @@
<?xml version="1.0" ?>
<sdf version="1.4">
<!--
cd ~/catkin_ws/src/gazebo_ros_pkgs/gazebo_plugins/test/projector
GAZEBO_RESOURCE_PATH=`pwd` roslaunch gazebo_plugins projector.test gui:=true
rostopic pub /projector_plugin/projector std_msgs/Int32 "data: 0"
rostopic pub /projector_plugin/projector std_msgs/Int32 "data: 1"
-->
<world name="default">
<include>
<uri>model://ground_plane</uri>
</include>

<!-- Global light source -->
<include>
<uri>model://sun</uri>
</include>

<!-- Focus camera on tall pendulum -->
<gui fullscreen='0'>
<camera name='user_camera'>
<pose>4.927360 -4.376610 3.740080 0.000000 0.275643 2.356190</pose>
<view_controller>orbit</view_controller>
</camera>
</gui>

<model name="model_1">
<static>false</static>
<pose>2.0 0.0 4.0 0.0 0.0 0.0</pose>
<link name="link_1">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertial>
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<inertia>
<ixx>1.0</ixx>
<ixy>0.0</ixy>
<ixz>0.0</ixz>
<iyy>1.0</iyy>
<iyz>0.0</iyz>
<izz>1.0</izz>
</inertia>
<mass>10.0</mass>
</inertial>
<visual name="visual_sphere">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<material>
<ambient>0.03 0.5 0.5 1.0</ambient>
<script>Gazebo/Green</script>
</material>
<cast_shadows>true</cast_shadows>
<laser_retro>100.0</laser_retro>
</visual>
<collision name="collision_sphere">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<max_contacts>250</max_contacts>
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>0.5</mu>
<mu2>0.2</mu2>
<fdir1>1.0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>1000000.0</threshold>
</bounce>
<contact>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e15</kp>
<kd>1e13</kd>
<max_vel>100.0</max_vel>
<min_depth>0.0001</min_depth>
</ode>
</contact>
</surface>
<laser_retro>100.0</laser_retro>
</collision>
</link>
</model>

<model name="projector_model">
<static>true</static>
<pose>0.0 0.0 0.5 0.0 0.0 0.0</pose>
<link name="projector_link">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<projector name="projector_plugin_test">
<pose>0 0 0 0 0 0</pose>
<texture>checker.png</texture>
<fov>1.4</fov>
<near_clip>0.1</near_clip>
<far_clip>6</far_clip>
</projector>
</link>
<plugin name="projector_plugin" filename="libgazebo_ros_projector.so">
<projector>projector_link/projector_plugin_test</projector>
<alwaysOn>false</alwaysOn>
<updateRate>15.0</updateRate>
<textureName>checker.png</textureName>
<textureTopicName>projector_plugin/image</textureTopicName>
<projectorTopicName>projector_plugin/projector</projectorTopicName>
</plugin>
</model>


<model name="projector_model2">
<static>true</static>
<pose>0.25 0.0 0.5 0.0 0.0 0.0</pose>
<link name="projector_link2">
<pose>0.0 0.0 0.0 0.0 0.0 0.0</pose>
<projector name="projector_plugin_test2">
<pose>0 0 0 0 0 0</pose>
<texture>checker.png</texture>
<fov>1.4</fov>
<near_clip>0.1</near_clip>
<far_clip>6</far_clip>
</projector>
</link>
<plugin name="projector_plugin2" filename="libgazebo_ros_projector.so">
<projector>projector_link2/projector_plugin_test2</projector>
<alwaysOn>false</alwaysOn>
<updateRate>15.0</updateRate>
<textureName>checker.png</textureName>
<textureTopicName>projector_plugin2/image</textureTopicName>
<projectorTopicName>projector_plugin2/projector</projectorTopicName>
</plugin>
</model>

</world>
</sdf>
49 changes: 49 additions & 0 deletions gazebo_plugins/test/projector/projector.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:arg name="laser_texture"
default="$(find gazebo_plugins)/test/projector/checker.png" />

<link name="world"/>

<joint name="joint_projector" type="fixed">
<origin xyz="0 0 2.0" rpy="0.0 0 0" />
<parent link="world" />
<child link="link_projector" />
</joint>

<link name="link_projector">
<visual>
<geometry>
<cylinder length="0.2" radius="0.05" />
</geometry>
</visual>
<inertial>
<mass value="1.0"/>
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
</inertial>
</link>

<gazebo reference="link_projector">
<projector name="projector_test_1">
<!-- setting the pose will produce glitches even when attached to a revolute joint -->
<pose>0 0 0 0 0 0</pose>
<texture>$(arg texture)</texture>
<fov>0.95</fov>
<near_clip>0.1</near_clip>
<far_clip>10.0</far_clip>
</projector>
</gazebo>
<gazebo>
<plugin name="projector_controller" filename="libgazebo_ros_projector.so">
<projector>link_projector/projector_test_1</projector>
<alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<textureName>$(arg texture)</textureName>
<!--filterTextureName>stereo_projection_pattern_filter.png</filterTextureName-->
<textureTopicName>projector_controller/image</textureTopicName>
<projectorTopicName>projector_controller/projector</projectorTopicName>
</plugin>
</gazebo>

</robot>
31 changes: 31 additions & 0 deletions gazebo_plugins/test/projector/toggle.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
#!/usr/bin/env python

import rospy
import unittest

from std_msgs.msg import Int32

class TestProjectorToggle(unittest.TestCase):
def setUp(self):
rospy.init_node('toggle')
def test_projector_toggle(self):
pub = rospy.Publisher("/projector_plugin/projector", Int32, queue_size=5)
pub2 = rospy.Publisher("/projector_plugin2/projector", Int32, queue_size=5)
toggle = True
start_time = None
while not rospy.is_shutdown():
for i in range(3):
pub.publish(Int32(int(toggle)))
pub2.publish(Int32(int(not toggle)))
toggle = not toggle
rospy.sleep(0.5)
cur_time = rospy.Time.now().to_sec()
if start_time is None:
start_time = cur_time
if cur_time - start_time > 10:
break
# print cur_time - start_time, start_time, cur_time

if __name__ == '__main__':
import rostest
rostest.rosrun('gazebo_plugins', 'test_projector_toggle', TestProjectorToggle)