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

Add PTZ sim support #125

Merged
merged 4 commits into from
Dec 6, 2024
Merged
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
Original file line number Diff line number Diff line change
Expand Up @@ -152,12 +152,14 @@ def __init__(self, sensor: BaseCamera) -> None:

class AxisCameraDescription(CameraDescription):
MODEL = 'model'
UPDATE_RATE = 'update_rate'

def __init__(self, sensor: AxisCamera) -> None:
super().__init__(sensor)

self.parameters.update({
self.MODEL: sensor.device_type
self.MODEL: sensor.device_type,
self.UPDATE_RATE: 15,
})

class IntelRealsenseDescription(CameraDescription):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -366,7 +366,7 @@
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</xacro:if>
<xacro:if value="${sim_ignition}">
<plugin>gz_ros2_control/IgnitionSystem</plugin>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</xacro:if>
<xacro:if value="${sim_isaac}">
<plugin>topic_based_ros2_control/TopicBasedSystem</plugin>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -480,7 +480,7 @@
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</xacro:if>
<xacro:if value="${sim_ignition}">
<plugin>gz_ros2_control/IgnitionSystem</plugin>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</xacro:if>
<xacro:if value="${sim_isaac}">
<plugin>topic_based_ros2_control/TopicBasedSystem</plugin>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -251,7 +251,7 @@
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</xacro:if>
<xacro:if value="${sim_ignition}">
<plugin>gz_ros2_control/IgnitionSystem</plugin>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</xacro:if>
<xacro:if value="${sim_isaac}">
<plugin>topic_based_ros2_control/TopicBasedSystem</plugin>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -203,7 +203,7 @@
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</xacro:if>
<xacro:if value="${sim_ignition}">
<plugin>gz_ros2_control/IgnitionSystem</plugin>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</xacro:if>
<xacro:if value="${use_fake_hardware}">
<plugin>mock_components/GenericSystem</plugin>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,7 @@
<param name="joint_states_topic">${isaac_joint_states}</param>
</xacro:if>
<xacro:if value="${sim_gazebo}">
<plugin>gz_ros2_control/IgnitionSystem</plugin>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</xacro:if>
<xacro:if value="${use_fake_hardware}">
<plugin>mock_components/GenericSystem</plugin>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@
<ros2_control name="a300_hardware" type="system">
<hardware>
<xacro:if value="$(arg is_sim)">
<plugin>ign_ros2_control/IgnitionSystem</plugin>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</xacro:if>
<xacro:unless value="$(arg is_sim)">
<plugin>clearpath_hardware_interfaces/LynxHardware</plugin>
Expand Down
Binary file removed clearpath_sensors_description/meshes/axis_dome.stl
Binary file not shown.
Binary file not shown.
Binary file not shown.
1 change: 1 addition & 0 deletions clearpath_sensors_description/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@

<buildtool_depend>ament_cmake</buildtool_depend>

<exec_depend>axis_description</exec_depend>
<exec_depend>microstrain_inertial_description</exec_depend>
<exec_depend>realsense2_description</exec_depend>
<exec_depend>velodyne_description</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
</inertial>
<visual>
<geometry>
<mesh filename="package://clearpath_sensors_description/meshes/axis_dome.stl" scale="1 1 1" />
<mesh filename="package://axis_description/meshes/axis_dome.stl" scale="1 1 1" />
</geometry>
<material name="axis_white">
<color rgba="0.8 0.8 0.8 1.0" />
Expand Down Expand Up @@ -47,37 +47,40 @@
<child link="${prefix}_base_link" />
</joint>

<link name="${prefix}_camera_link" />
<link name="${prefix}_link" />
<joint name="${prefix}_camera_joint" type="fixed">
<parent link="${prefix}_base_link" />
<child link="${prefix}_camera_link" />
<child link="${prefix}_link" />
<origin xyz="0.047 0 ${stand_height + 0.09 + 0.047}" rpy="0 0.7854 0" />
</joint>

<gazebo reference="${prefix}_camera_link">
<material>Gazebo/Black</material>
<sensor type="camera" name="${prefix}_dome_camera">
<!--
Simulation support: sensor plugin
-->
<gazebo reference="${prefix}_link">
<plugin filename="libgz-sim-sensors-system.so" name="gz::sim::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>

<sensor name="${prefix}_camera" type="camera">
<update_rate>15</update_rate>
<visualize>true</visualize>
<always_on>true</always_on>
<gz_frame_id>${prefix}_link</gz_frame_id>
<topic>$(arg namespace)/sensors/${prefix}/image</topic>
<camera>
<horizontal_fov>6.28</horizontal_fov>
<vertical_fov>1.57</vertical_fov>
<horizontal_fov>1.5184351666666667</horizontal_fov>
<vertical_fov>1.0122901111111111</vertical_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>500.0</far>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<plugin name="${prefix}_camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<cameraName>${prefix}_camera</cameraName>
<imageTopicName>${topic}</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>${prefix}_camera_link</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
Expand Down
61 changes: 28 additions & 33 deletions clearpath_sensors_description/urdf/axis/axis_dome_ptz.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
</inertial>
<visual>
<geometry>
<mesh filename="package://clearpath_sensors_description/meshes/axis_dome.stl" scale="1 1 1" />
<mesh filename="package://axis_description/meshes/axis_dome.stl" scale="1 1 1" />
</geometry>
<material name="axis_white">
<color rgba="0.8 0.8 0.8 1.0" />
Expand Down Expand Up @@ -88,38 +88,40 @@
<!--
Add the gazebo reference frame
-->
<link name="${prefix}_camera_link" />
<link name="${prefix}_link" />
<joint name="${prefix}_camera_joint" type="fixed">
<parent link="${prefix}_head_link" />
<child link="${prefix}_camera_link" />
<child link="${prefix}_link" />
<origin xyz="0.067 0 0" rpy="0 0 0" />
</joint>

<!--
Simulation support: camera plugin & transmissions to allow control over the joints
Simulation support: sensor and joint controller plugins
Velocity control is limited to the real-world camera's limits
-->
<transmission name="${prefix}_pan_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}_pan_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}_pan_actuator">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${prefix}_tilt_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}_tilt_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}_tilt_actuator">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<gazebo reference="${prefix}_camera_link">
<gazebo>
<plugin filename="libgz-sim-joint-controller-system.so" name="gz::sim::systems::JointController">
<joint_name>${prefix}_pan_joint</joint_name>
<cmd_min>-2.61</cmd_min>
<cmd_max>2.61</cmd_max>
<topic>$(arg namespace)/sensors/${prefix}/cmd_pan_vel</topic>
</plugin>
<plugin filename="libgz-sim-joint-controller-system.so" name="gz::sim::systems::JointController">
<joint_name>${prefix}_tilt_joint</joint_name>
<cmd_min>2.61</cmd_min>
<cmd_max>2.61</cmd_max>
<topic>$(arg namespace)/sensors/${prefix}/cmd_tilt_vel</topic>
</plugin>
</gazebo>
<gazebo reference="${prefix}_link">
<material>Gazebo/Black</material>
<sensor type="camera" name="${prefix}_ptz_camera">

<sensor name="${prefix}_camera" type="camera">
<update_rate>15</update_rate>
<visualize>true</visualize>
<always_on>true</always_on>
<gz_frame_id>${prefix}_link</gz_frame_id>
<topic>$(arg namespace)/sensors/${prefix}/image</topic>
<camera>
<horizontal_fov>1.5184351666666667</horizontal_fov>
<vertical_fov>1.0122901111111111</vertical_fov>
Expand All @@ -129,17 +131,10 @@
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>500.0</far>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<plugin name="${prefix}_camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<cameraName>${prefix}_camera</cameraName>
<imageTopicName>${topic}</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>${prefix}_camera_link</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
Expand Down
85 changes: 43 additions & 42 deletions clearpath_sensors_description/urdf/axis/axis_q62.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:macro name="axis_q62" params="prefix parent topic *origin">
<xacro:macro name="axis_q62" params="prefix parent *origin">
<link name="${prefix}_base_link">
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
Expand Down Expand Up @@ -28,7 +28,7 @@
</inertial>
<visual>
<geometry>
<mesh filename="package://clearpath_sensors_description/meshes/axis_q62_base.stl" scale="0.001 0.001 0.001" />
<mesh filename="package://axis_description/meshes/axis_q62_base.stl" scale="0.001 0.001 0.001" />
</geometry>
<material name="axis_grey">
<color rgba="0.7 0.7 0.7 1.0" />
Expand Down Expand Up @@ -63,7 +63,7 @@
</inertial>
<visual>
<geometry>
<mesh filename="package://clearpath_sensors_description/meshes/axis_q62_top.stl" scale="0.001 0.001 0.001" />
<mesh filename="package://axis_description/meshes/axis_q62_top.stl" scale="0.001 0.001 0.001" />
</geometry>
<material name="axis_grey">
<color rgba="0.7 0.7 0.7 1.0" />
Expand Down Expand Up @@ -91,57 +91,65 @@
<!--
Add the shades & gazebo reference frame
-->
<link name="${prefix}_camera_link">
<link name="${prefix}_link">
<visual>
<geometry>
<box size="0.03 0.09 0.01" />
</geometry>
<origin xyz="-0.01 0 0.05" rpy="0 0 0" />
<material name="axis_black">
<color rgba="0 0 0 1" />
</material>
<material name="black" />
</visual>
<visual>
<geometry>
<box size="0.03 0.09 0.01" />
</geometry>
<origin xyz="-0.01 0.20 0.05" rpy="0 0 0" />
<material name="axis_black">
<color rgba="0 0 0 1" />
</material>
<material name="black" />
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="1" />
<inertia
ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0" />
</inertial>
</link>
<joint name="${prefix}_camera_joint" type="fixed">
<parent link="${prefix}_head_link" />
<child link="${prefix}_camera_link" />
<child link="${prefix}_link" />
<origin xyz="0.1 -0.107 0" rpy="0 0 0" />
</joint>

<!--
Simulation support: camera plugin & transmissions to allow control over the joints
Simulation support: sensor and joint controller plugins
Velocity control is limited to the real-world camera's limits
-->
<transmission name="${prefix}_pan_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}_pan_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}_pan_actuator">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="${prefix}_tilt_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}_tilt_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}_tilt_actuator">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<gazebo reference="${prefix}_camera_link">
<material>Gazebo/Black</material>
<sensor type="camera" name="${prefix}_ptz_camera">
<gazebo>
<plugin filename="libgz-sim-joint-controller-system.so" name="gz::sim::systems::JointController">
<joint_name>${prefix}_pan_joint</joint_name>
<cmd_min>-2.61</cmd_min>
<cmd_max>2.61</cmd_max>
<topic>$(arg namespace)/sensors/${prefix}/cmd_pan_vel</topic>
</plugin>
<plugin filename="libgz-sim-joint-controller-system.so" name="gz::sim::systems::JointController">
<joint_name>${prefix}_tilt_joint</joint_name>
<cmd_min>2.61</cmd_min>
<cmd_max>2.61</cmd_max>
<topic>$(arg namespace)/sensors/${prefix}/cmd_tilt_vel</topic>
</plugin>
</gazebo>
<gazebo reference="${prefix}_link">
<plugin filename="libgz-sim-sensors-system.so" name="gz::sim::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>

<sensor name="${prefix}_camera" type="camera">
<update_rate>15</update_rate>
<visualize>true</visualize>
<always_on>true</always_on>
<gz_frame_id>${prefix}_link</gz_frame_id>
<topic>$(arg namespace)/sensors/${prefix}/image</topic>
<camera>
<horizontal_fov>1.5184351666666667</horizontal_fov>
<vertical_fov>1.0122901111111111</vertical_fov>
Expand All @@ -151,17 +159,10 @@
<format>R8G8B8</format>
</image>
<clip>
<near>0.05</near>
<far>500.0</far>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<plugin name="${prefix}_camera_controller" filename="libgazebo_ros_camera.so">
<alwaysOn>true</alwaysOn>
<cameraName>${prefix}_camera</cameraName>
<imageTopicName>${topic}</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>${prefix}_camera_link</frameName>
</plugin>
</sensor>
</gazebo>
</xacro:macro>
Expand Down
Loading
Loading