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

Updated branch based on recommended PR changes #464

Merged
merged 4 commits into from
Jun 18, 2020
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
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,10 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw)
<wheel_separation>#{0.45649 * 1.5}</wheel_separation>
<wheel_radius>0.1651</wheel_radius>
<topic>/model/#{_name}/cmd_vel_relay</topic>
<min_velocity>-1</min_velocity>
<max_velocity>1</max_velocity>
<min_acceleration>-2</min_acceleration>
<max_acceleration>3</max_acceleration>
</plugin>
<!-- Publish robot state information -->
<plugin filename="libignition-gazebo-pose-publisher-system.so"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -107,6 +107,23 @@
args="$(arg sensor_prefix)/camera_front/depth_image">
<remap from="$(arg sensor_prefix)/camera_front/depth_image" to="front_facing/depth"/>
</node>
<node
pkg="subt_ros"
type="optical_frame_publisher"
name="optical_frame_publisher_image_front_facing">
<remap from="input/image" to="front_facing/image_raw" />
<remap from="output/image" to="front_facing/optical/image_raw" />
<remap from="input/camera_info" to="front_facing/camera_info" />
<remap from="output/camera_info" to="front_facing/optical/camera_info" />
</node>
<node
pkg="subt_ros"
type="optical_frame_publisher"
name="optical_frame_publisher_depth_front"
args="depth">
<remap from="input/image" to="front_facing/depth" />
<remap from="output/image" to="front_facing/optical/depth" />
</node>

<!--30 Degree downward looking RGBD camera -->
<node
Expand Down Expand Up @@ -137,6 +154,23 @@
args="$(arg sensor_prefix)/camera_down/depth_image">
<remap from="$(arg sensor_prefix)/camera_down/depth_image" to="front_down/depth"/>
</node>
<node
pkg="subt_ros"
type="optical_frame_publisher"
name="optical_frame_publisher_image_front_down">
<remap from="input/image" to="front_down/image_raw" />
<remap from="output/image" to="front_down/optical/image_raw" />
<remap from="input/camera_info" to="front_down/camera_info" />
<remap from="output/camera_info" to="front_down/optical/camera_info" />
</node>
<node
pkg="subt_ros"
type="optical_frame_publisher"
name="optical_frame_publisher_depth_down"
args="depth">
<remap from="input/image" to="front_down/depth" />
<remap from="output/image" to="front_down/optical/depth" />
</node>

<!--Pan Tilt RGBD camera -->
<node
Expand Down Expand Up @@ -167,6 +201,23 @@
args="$(arg gimbal_sensor_prefix)/camera_pan_tilt/depth_image">
<remap from="$(arg gimbal_sensor_prefix)/camera_pan_tilt/depth_image" to="pan_tilt/depth"/>
</node>
<node
pkg="subt_ros"
type="optical_frame_publisher"
name="optical_frame_publisher_image_pan_tilt">
<remap from="input/image" to="pan_tilt/image_raw" />
<remap from="output/image" to="pan_tilt/optical/image_raw" />
<remap from="input/camera_info" to="pan_tilt/camera_info" />
<remap from="output/camera_info" to="pan_tilt/optical/camera_info" />
</node>
<node
pkg="subt_ros"
type="optical_frame_publisher"
name="optical_frame_publisher_depth_pan_tilt"
args="depth">
<remap from="input/image" to="pan_tilt/depth" />
<remap from="output/image" to="pan_tilt/optical/depth" />
</node>

<!--OS1-64 3D Laser-->
<node
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,10 @@ def spawner(_name, _modelURI, _worldName, _x, _y, _z, _roll, _pitch, _yaw)
" <wheel_separation>#{0.33559 * 1.23}</wheel_separation>\n"\
" <wheel_radius>0.098</wheel_radius>\n"\
" <topic>/model/#{_name}/cmd_vel_relay</topic>\n"\
" <min_velocity>-1</min_velocity>\n"\
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Just checking, is this change from a robotika model on purpose?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I thought this was requested inside the model_pr_426-> master pull request? Perhaps it was by mistake?
robotica_x2

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, sorry for the confusion, I copied this comment from a different team.

" <max_velocity>1</max_velocity>\n"\
" <min_acceleration>-2</min_acceleration>\n"\
" <max_acceleration>3</max_acceleration>\n"\
" </plugin>\n"\
" <!-- Publish robot state information -->\n"\
" <plugin filename=\"libignition-gazebo-pose-publisher-system.so\"\n"\
Expand Down
4 changes: 2 additions & 2 deletions subt_ros/launch/competition_init.launch
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,10 @@
type="subt_ros_relay"
name="subt_ros_relay"/>

<!--<node
<node
pkg="subt_ros"
type="bridge_logger"
name="bridge_logger"/>-->
name="bridge_logger"/>


<node
Expand Down