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

Publish IR Opcodes #66

Merged
merged 9 commits into from
Oct 15, 2021
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
23 changes: 17 additions & 6 deletions irobot_create_description/urdf/create3.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -7,28 +7,29 @@
<xacro:include filename="$(find irobot_create_description)/urdf/sensors/cliff_sensor.urdf.xacro"/>
<xacro:include filename="$(find irobot_create_description)/urdf/sensors/imu.urdf.xacro" />
<xacro:include filename="$(find irobot_create_description)/urdf/sensors/ir_intensity.urdf.xacro" />
<xacro:include filename="$(find irobot_create_description)/urdf/sensors/ir_opcode_receivers.urdf.xacro" />
<xacro:include filename="$(find irobot_create_description)/urdf/sensors/optical_mouse.urdf.xacro"/>
<xacro:include filename="$(find irobot_create_description)/urdf/wheel_with_wheeldrop.urdf.xacro" />

<!-- MECHANICAL PROPERTIES -->
<xacro:property name="body_z_offset" value="${4.1*cm2m}" />
<xacro:property name="body_collision_z_offset" value="${1*cm2m}" />
<xacro:property name="body_z_offset" value="${-2.5*cm2m}" />
<xacro:property name="body_collision_z_offset" value="${-1*cm2m}" />
<xacro:property name="body_mass" value="2.300" />
<xacro:property name="body_radius" value="${16.4*cm2m}" />
<xacro:property name="body_length" value="${6*cm2m}" />

<xacro:property name="bumper_mass" value="0.1" />
<xacro:property name="bumper_offset_z" value="${4.1*cm2m}" />
<xacro:property name="bumper_offset_z" value="${-2.5*cm2m}" />
<xacro:property name="bumber_inertial_x" value="${8*cm2m}" />
<xacro:property name="bumper_inertial_z" value="${2*cm2m}"/>

<xacro:property name="wheel_height" value="${3.85*cm2m}" />
<xacro:property name="wheel_height" value="${-2.75*cm2m}" />
<xacro:property name="distance_between_wheels" value="${23.3*cm2m}" />

<xacro:property name="caster_position_x" value="${12.5*cm2m}" />
<xacro:property name="caster_position_z" value="${1.2*cm2m}" />
<xacro:property name="caster_position_z" value="${-5.4*cm2m}" />

<xacro:property name="wheel_drop_offset_z" value="${3.1*mm2m}"/>
<xacro:property name="wheel_drop_offset_z" value="${3.5*mm2m}"/>
<xacro:property name="wheel_drop_z" value="${wheel_height + wheel_drop_offset_z}"/>

<!-- Create 3 base definition-->
Expand Down Expand Up @@ -179,4 +180,14 @@
<origin xyz="0.06 0 0.08" rpy="0 ${-pi/2} 0"/>
</xacro:button>


<!-- Omni IR receiver (sensor 0) parameters and Front-facing IR receiver (sensor 1) parameters -->
<xacro:property name="ir_omni_fov_rad" value="${360*deg2rad}"/>
rjcausarano marked this conversation as resolved.
Show resolved Hide resolved
<xacro:property name="ir_front_facing_fov_rad" value="${90*deg2rad}"/>
rjcausarano marked this conversation as resolved.
Show resolved Hide resolved
<xacro:property name="ir_samples" value="72"/>
<xacro:ir_opcode_receivers sensor_0_range="1" sensor_0_fov="${ir_omni_fov_rad}"
sensor_1_range="5" sensor_1_fov="${ir_front_facing_fov_rad}" samples="${ir_samples}" visualize="true" >
<origin xyz="0.153 0 0.035"/>
</xacro:ir_opcode_receivers>

</robot>
25 changes: 6 additions & 19 deletions irobot_create_description/urdf/dock/ir_emitter.urdf.xacro
Original file line number Diff line number Diff line change
@@ -1,9 +1,10 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="ir_emitter" params="name parent:=base_link *origin
range code aperture
update_rate:=20 broadcast_rate:=64
ros_topic:=ir_emitter min_range:=0.50
range
aperture
update_rate:=1
rjcausarano marked this conversation as resolved.
Show resolved Hide resolved
min_range:=${7*cm2m}
visualize:=false" >

<!-- Physical link properties -->
Expand All @@ -30,7 +31,6 @@
</link>

<gazebo reference="${name}_link">
<preserveFixedJoint>true</preserveFixedJoint>
rjcausarano marked this conversation as resolved.
Show resolved Hide resolved
<sensor type="ray" name="${name}">
<always_on>true</always_on>
<update_rate>${update_rate}</update_rate>
Expand All @@ -51,23 +51,10 @@
</range>
</ray>
</sensor>
<material>Gazebo/Red</material>
<static>true</static>
</gazebo>

<gazebo>
<static>true</static>
<!-- MOVE TO SENSOR PLUGIN -->
<!-- <plugin name="${name}_ir_emitter" filename="libgazebo_ros_irobot_ir_emitter.so">
<link>${name}_link</link>
<topicName>${ros_topic}</topicName>
<emitterName>${name}</emitterName>
<emitterCode>${code}</emitterCode>
<rayAperture>${aperture}</rayAperture>
<rayRange>${range}</rayRange>
<updateRate>${update_rate}</updateRate>
<broadcastRate>${broadcast_rate}</broadcastRate>
</plugin> -->
<gazebo reference="${name}_joint" >
<preserveFixedJoint>true</preserveFixedJoint>
</gazebo>

</xacro:macro>
Expand Down
54 changes: 19 additions & 35 deletions irobot_create_description/urdf/dock/standard.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,12 @@
<xacro:include filename="$(find irobot_create_description)/urdf/common_properties.urdf.xacro"/>
<xacro:include filename="$(find irobot_create_description)/urdf/dock/ir_emitter.urdf.xacro"/>

<xacro:property name="z_offset_mm" value="4.6"/>
<xacro:property name="link_name" value="std_dock_link"/>
<xacro:property name="z_offset" value="${4.6*mm2m}"/>
<xacro:property name="link_name" value="std_dock_link"/>
rjcausarano marked this conversation as resolved.
Show resolved Hide resolved

<link name="${link_name}">
<visual>
<origin xyz="0 0 ${z_offset_mm*mm2m}"/>
<origin xyz="0 0 ${z_offset}"/>
<geometry>
<mesh filename="file://$(find irobot_create_description)/meshes/dock/visual.dae"/>
</geometry>
Expand All @@ -20,19 +20,12 @@
<box size="0.04 0.13 0.1"/>
</geometry>
</collision>
<xacro:inertial_dummy />
rjcausarano marked this conversation as resolved.
Show resolved Hide resolved
</link>

<gazebo reference="${link_name}">
<mu1>1.0</mu1>
<mu2>1.0</mu2>
<kp>1000000.0</kp>
<kd>1.0</kd>
</gazebo>

<!-- Parameters for IR emitters -->
<xacro:property name="buoy_x" value="-0.037"/>
<xacro:property name="buoy_y" value="0.005"/>
<xacro:property name="buoy_z" value="${0.065 - (z_offset_mm*mm2m)}"/>
<xacro:property name="buoy_x" value="${-6*cm2m}"/>
<xacro:property name="buoy_z" value="${0.065 - z_offset}"/>

<xacro:property name="halo_name" value="halo"/>
rjcausarano marked this conversation as resolved.
Show resolved Hide resolved
<xacro:property name="green_buoy_name" value="green_buoy"/>
Expand All @@ -45,51 +38,42 @@
<!-- Green IR emitter -->
<xacro:ir_emitter name="${green_buoy_name}"
parent="${link_name}"
code="164"
aperture="${buoy_lateral_aperture}"
range="1.524">
<origin xyz="${buoy_x} ${- buoy_y} ${buoy_z}"
range="1.524"
visualize="true">
rjcausarano marked this conversation as resolved.
Show resolved Hide resolved
<origin xyz="${buoy_x} 0 ${buoy_z}"
rpy="0 0 ${- buoy_lateral_angle_yaw}"/>
</xacro:ir_emitter>

<!-- Red IR emitter -->
<xacro:ir_emitter name="${red_buoy_name}"
parent="${link_name}"
code="168"
aperture="${buoy_lateral_aperture}"
range="1.524">
<origin xyz="${buoy_x} ${buoy_y} ${buoy_z}"
range="1.524"
visualize="true">
rjcausarano marked this conversation as resolved.
Show resolved Hide resolved
<origin xyz="${buoy_x} 0 ${buoy_z}"
rpy="0 0 ${buoy_lateral_angle_yaw}"/>
</xacro:ir_emitter>

<!-- Yellow IR emitter -->
<xacro:ir_emitter name="${yellow_buoy_name}"
parent="${link_name}"
code="172"
aperture="${10*deg2rad}"
range="1.2192">
range="1.2192"
visualize="true">
<origin xyz="${buoy_x} 0 ${buoy_z}"/>
</xacro:ir_emitter>

<!-- Halo IR emitter -->
<xacro:ir_emitter name="${halo_name}"
parent="${link_name}"
code="161"
aperture="360"
range="0.6096">
<origin xyz="-0.052 0 ${0.095 - (z_offset_mm*mm2m)}"/>
range="0.6096"
visualize="true">
<origin xyz="${buoy_x} 0 ${0.095 - z_offset}"/>
</xacro:ir_emitter>

<xacro:property name="real_behavior" value="$(arg real_behavior)"/>
<gazebo>
<static>true</static>
<!-- <plugin name="gazebo_ros_dock_manager" filename="libgazebo_ros_irobot_dock_manager.so">
<halo>${halo_name}</halo>
<greenBuoy>${green_buoy_name}</greenBuoy>
<redBuoy>${red_buoy_name}</redBuoy>
<yellowBuoy>${yellow_buoy_name}</yellowBuoy>
<realBehavior>${real_behavior}</realBehavior>
</plugin> -->
</gazebo>

<static>true</static>
</gazebo>
</robot>
Original file line number Diff line number Diff line change
@@ -0,0 +1,98 @@
<?xml version="1.0"?>

<robot xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:macro name="ir_opcode_receivers" params="name:=ir_omni
parent:=base_link
sensor_0_fov
sensor_0_range
sensor_1_fov
sensor_1_range
samples
min_range:=0.015
update_rate:=31
visualize:=false
*origin" >

<xacro:property name="joint_name" value="${name}_joint" />
<xacro:property name="link_name" value="${name}" />

<joint name="${joint_name}" type="fixed">
<xacro:insert_block name="origin" />
<parent link="${parent}"/>
<child link="${link_name}"/>
</joint>

<link name="${link_name}">
<xacro:inertial_dummy />
</link>

<!-- Sensor 0 visualization -->
<gazebo reference="${link_name}">
<sensor type="ray" name="sensor_0">
<always_on>true</always_on>
<update_rate>1</update_rate>
rjcausarano marked this conversation as resolved.
Show resolved Hide resolved
<visualize>${visualize}</visualize>
<ray>
<scan>
<horizontal>
<samples>${samples}</samples>
<resolution>1</resolution>
<min_angle>${-sensor_0_fov/2}</min_angle>
<max_angle>${sensor_0_fov/2}</max_angle>
</horizontal>
</scan>
<range>
<min>${min_range}</min>
<max>${sensor_0_range}</max>
<resolution>0.01</resolution>
</range>
</ray>
</sensor>
</gazebo>

<!-- Sensor 1 visualization -->
<gazebo reference="${link_name}">
<sensor type="ray" name="sensor_1">
<always_on>true</always_on>
<update_rate>1</update_rate>
<visualize>${visualize}</visualize>
<ray>
<scan>
<horizontal>
<samples>${samples}</samples>
<resolution>1</resolution>
<min_angle>${-sensor_1_fov/2}</min_angle>
<max_angle>${sensor_1_fov/2}</max_angle>
</horizontal>
</scan>
<range>
<min>${min_range}</min>
<max>${sensor_1_range}</max>
<resolution>0.01</resolution>
</range>
</ray>
</sensor>
</gazebo>

<gazebo>
<plugin name="${name}_plugin" filename="libgazebo_ros_create_ir_opcodes.so">
<ros>
<namespace>/</namespace>
<remapping>~/out:=ir_opcode</remapping>
</ros>
<update_rate>${update_rate}</update_rate>
<link_name>${link_name}</link_name>
<sensor_0_fov>${sensor_0_fov}</sensor_0_fov>
<sensor_0_range>${sensor_0_range}</sensor_0_range>
<sensor_1_fov>${sensor_1_fov}</sensor_1_fov>
<sensor_1_range>${sensor_1_range}</sensor_1_range>
</plugin>
</gazebo>

<gazebo reference="${joint_name}" >
<preserveFixedJoint>true</preserveFixedJoint>
</gazebo>

</xacro:macro>
</robot>
31 changes: 31 additions & 0 deletions irobot_create_gazebo_plugins/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,14 @@ add_library(gazebo_ros_create_optical_mouse SHARED
src/gazebo_ros_optical_mouse.cpp
)

add_library(gazebo_ros_create_ir_opcodes SHARED
rjcausarano marked this conversation as resolved.
Show resolved Hide resolved
src/gazebo_ros_ir_opcode.cpp
rjcausarano marked this conversation as resolved.
Show resolved Hide resolved
)

add_library(docking_manager SHARED
src/docking_manager.cpp
)

add_library(gazebo_ros_create_wheel_drop SHARED
src/gazebo_ros_wheel_drop.cpp
)
Expand Down Expand Up @@ -114,6 +122,27 @@ ament_target_dependencies(gazebo_ros_create_optical_mouse
ament_export_libraries(gazebo_ros_create_optical_mouse)
target_link_libraries(gazebo_ros_create_optical_mouse gazebo_ros_create_helpers)

## gazebo_ros_create_ir_opcodes
target_include_directories(gazebo_ros_create_ir_opcodes PUBLIC include)
ament_target_dependencies(gazebo_ros_create_ir_opcodes
"gazebo_dev"
"gazebo_ros"
"irobot_create_msgs"
"rclcpp"
)
ament_export_libraries(gazebo_ros_create_ir_opcodes)
target_link_libraries(gazebo_ros_create_ir_opcodes gazebo_ros_create_helpers docking_manager)

## docking_manager
target_include_directories(docking_manager PUBLIC include)
ament_target_dependencies(docking_manager
"gazebo_dev"
"gazebo_ros"
"rclcpp"
)
ament_export_libraries(docking_manager)
target_link_libraries(docking_manager gazebo_ros_create_helpers)

## gazebo_ros_create_wheel_drop
target_include_directories(gazebo_ros_create_wheel_drop PUBLIC include)
ament_target_dependencies(gazebo_ros_create_wheel_drop
Expand Down Expand Up @@ -141,6 +170,8 @@ install(TARGETS
gazebo_ros_create_imu
gazebo_ros_create_ir_intensity_sensor
gazebo_ros_create_optical_mouse
gazebo_ros_create_ir_opcodes
docking_manager
gazebo_ros_create_wheel_drop
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
Expand Down
Loading