mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-08 18:21:15 +00:00
Added full end effector transports.
This commit is contained in:
@@ -16,13 +16,13 @@ import RoverVideoReceiver
|
||||
CAMERA_TOPIC_PATH = "/cameras/"
|
||||
EXCLUDED_CAMERAS = ["zed"]
|
||||
#
|
||||
PRIMARY_LABEL_MAX = (640, 360)
|
||||
SECONDARY_LABEL_MAX = (256, 144)
|
||||
TERTIARY_LABEL_MAX = (256, 144)
|
||||
# PRIMARY_LABEL_MAX = (640, 360)
|
||||
# SECONDARY_LABEL_MAX = (256, 144)
|
||||
# TERTIARY_LABEL_MAX = (256, 144)
|
||||
|
||||
# PRIMARY_LABEL_MAX = (1280, 720)
|
||||
# SECONDARY_LABEL_MAX = (640, 360)
|
||||
# TERTIARY_LABEL_MAX = (640, 360)
|
||||
PRIMARY_LABEL_MAX = (1280, 720)
|
||||
SECONDARY_LABEL_MAX = (640, 360)
|
||||
TERTIARY_LABEL_MAX = (640, 360)
|
||||
|
||||
|
||||
#####################################
|
||||
|
||||
@@ -1,5 +0,0 @@
|
||||
topics:
|
||||
- name: "/drive/motoroneandtwo"
|
||||
compress: true # enable bz2 compression
|
||||
rate: 20.0 # rate limit at 1Hz
|
||||
- name: "/my_second_topic"
|
||||
@@ -33,9 +33,9 @@ public:
|
||||
node_handle->param("small_image_width", small_image_width, 256);
|
||||
node_handle->param("small_image_height", small_image_height, 144);
|
||||
|
||||
broadcast_large_image = true;
|
||||
broadcast_large_image = false;
|
||||
broadcast_medium_image = false;
|
||||
broadcast_small_image = false;
|
||||
broadcast_small_image = true;
|
||||
|
||||
if(is_rtsp_camera){
|
||||
cap = new cv::VideoCapture(capture_device_path);
|
||||
|
||||
@@ -58,7 +58,6 @@ class DriveCoordinator(object):
|
||||
self.left_bogie_publisher = rospy.Publisher(self.left_bogie_topic, DriveControlMessage, queue_size=1)
|
||||
self.right_bogie_publisher = rospy.Publisher(self.right_bogie_topic, DriveControlMessage, queue_size=1)
|
||||
|
||||
# Other Vars TODO: fix this later
|
||||
self.drive_command_data = {
|
||||
"iris": {
|
||||
"message": DriveCommandMessage(),
|
||||
|
||||
@@ -1,36 +1,51 @@
|
||||
<launch>
|
||||
<group ns="cameras">
|
||||
<node name="chassis_640x360" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<node name="chassis_1280x720" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<param name="port" value="17001" />
|
||||
</node>
|
||||
|
||||
<node name="undercarriage_640x360" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<node name="undercarriage_1280x720" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<param name="port" value="17002" />
|
||||
</node>
|
||||
|
||||
<node name="main_navigation_640x360" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<node name="main_navigation_1280x720" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<param name="port" value="17003" />
|
||||
</node>
|
||||
|
||||
<node name="end_effector_640x360" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<node name="end_effector_1280x720" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<param name="port" value="17004" />
|
||||
</node>
|
||||
|
||||
<node name="chassis_256x144" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<node name="chassis_640x360" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<param name="port" value="17005" />
|
||||
</node>
|
||||
|
||||
<node name="undercarriage_256x144" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<node name="undercarriage_640x360" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<param name="port" value="17006" />
|
||||
</node>
|
||||
|
||||
<node name="main_navigation_256x144" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<node name="main_navigation_640x360" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<param name="port" value="17007" />
|
||||
</node>
|
||||
|
||||
<node name="end_effector_256x144" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<node name="end_effector_640x360" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<param name="port" value="17008" />
|
||||
</node>
|
||||
|
||||
<node name="chassis_256x144" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<param name="port" value="17009" />
|
||||
</node>
|
||||
|
||||
<node name="undercarriage_256x144" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<param name="port" value="17010" />
|
||||
</node>
|
||||
|
||||
<node name="main_navigation_256x144" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<param name="port" value="17011" />
|
||||
</node>
|
||||
|
||||
<node name="end_effector_256x144" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
|
||||
<param name="port" value="17012" />
|
||||
</node>
|
||||
</group>
|
||||
</launch>
|
||||
|
||||
@@ -2,9 +2,41 @@
|
||||
<group ns="sender_transports">
|
||||
<arg name="target" default="192.168.1.15" />
|
||||
|
||||
<node name="chassis_640x360" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
|
||||
<node name="chassis_1280x720" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
|
||||
<param name="destination_addr" value="$(arg target)" />
|
||||
<param name="destination_port" value="17001" />
|
||||
<rosparam param="topics">
|
||||
[{name: "/cameras/chassis/image_1280x720/compressed", compress: false, rate: 30.0}]
|
||||
</rosparam>
|
||||
</node>
|
||||
|
||||
<node name="undercarriage_1280x720" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
|
||||
<param name="destination_addr" value="$(arg target)" />
|
||||
<param name="destination_port" value="17002" />
|
||||
<rosparam param="topics">
|
||||
[{name: "/cameras/undercarriage/image_1280x720/compressed", compress: false, rate: 30.0}]
|
||||
</rosparam>
|
||||
</node>
|
||||
|
||||
<node name="main_navigation_1280x720" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
|
||||
<param name="destination_addr" value="$(arg target)" />
|
||||
<param name="destination_port" value="17003" />
|
||||
<rosparam param="topics">
|
||||
[{name: "/cameras/main_navigation/image_1280x720/compressed", compress: false, rate: 30.0}]
|
||||
</rosparam>
|
||||
</node>
|
||||
|
||||
<node name="end_effector_1280x720" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
|
||||
<param name="destination_addr" value="$(arg target)" />
|
||||
<param name="destination_port" value="17004" />
|
||||
<rosparam param="topics">
|
||||
[{name: "/cameras/end_effector/image_1280x720/compressed", compress: false, rate: 30.0}]
|
||||
</rosparam>
|
||||
</node>
|
||||
|
||||
<node name="chassis_640x360" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
|
||||
<param name="destination_addr" value="$(arg target)" />
|
||||
<param name="destination_port" value="17005" />
|
||||
<rosparam param="topics">
|
||||
[{name: "/cameras/chassis/image_640x360/compressed", compress: false, rate: 30.0}]
|
||||
</rosparam>
|
||||
@@ -12,7 +44,7 @@
|
||||
|
||||
<node name="undercarriage_640x360" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
|
||||
<param name="destination_addr" value="$(arg target)" />
|
||||
<param name="destination_port" value="17002" />
|
||||
<param name="destination_port" value="17006" />
|
||||
<rosparam param="topics">
|
||||
[{name: "/cameras/undercarriage/image_640x360/compressed", compress: false, rate: 30.0}]
|
||||
</rosparam>
|
||||
@@ -20,7 +52,7 @@
|
||||
|
||||
<node name="main_navigation_640x360" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
|
||||
<param name="destination_addr" value="$(arg target)" />
|
||||
<param name="destination_port" value="17003" />
|
||||
<param name="destination_port" value="17007" />
|
||||
<rosparam param="topics">
|
||||
[{name: "/cameras/main_navigation/image_640x360/compressed", compress: false, rate: 30.0}]
|
||||
</rosparam>
|
||||
@@ -28,7 +60,7 @@
|
||||
|
||||
<node name="end_effector_640x360" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
|
||||
<param name="destination_addr" value="$(arg target)" />
|
||||
<param name="destination_port" value="17004" />
|
||||
<param name="destination_port" value="17008" />
|
||||
<rosparam param="topics">
|
||||
[{name: "/cameras/end_effector/image_640x360/compressed", compress: false, rate: 30.0}]
|
||||
</rosparam>
|
||||
@@ -36,7 +68,7 @@
|
||||
|
||||
<node name="chassis_256x144" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
|
||||
<param name="destination_addr" value="$(arg target)" />
|
||||
<param name="destination_port" value="17005" />
|
||||
<param name="destination_port" value="17009" />
|
||||
<rosparam param="topics">
|
||||
[{name: "/cameras/chassis/image_256x144/compressed", compress: false, rate: 30.0}]
|
||||
</rosparam>
|
||||
@@ -44,7 +76,7 @@
|
||||
|
||||
<node name="undercarriage_256x144" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
|
||||
<param name="destination_addr" value="$(arg target)" />
|
||||
<param name="destination_port" value="17006" />
|
||||
<param name="destination_port" value="17010" />
|
||||
<rosparam param="topics">
|
||||
[{name: "/cameras/undercarriage/image_256x144/compressed", compress: false, rate: 30.0}]
|
||||
</rosparam>
|
||||
@@ -52,7 +84,7 @@
|
||||
|
||||
<node name="main_navigation_256x144" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
|
||||
<param name="destination_addr" value="$(arg target)" />
|
||||
<param name="destination_port" value="17007" />
|
||||
<param name="destination_port" value="17011" />
|
||||
<rosparam param="topics">
|
||||
[{name: "/cameras/main_navigation/image_256x144/compressed", compress: false, rate: 30.0}]
|
||||
</rosparam>
|
||||
@@ -60,7 +92,7 @@
|
||||
|
||||
<node name="end_effector_256x144" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
|
||||
<param name="destination_addr" value="$(arg target)" />
|
||||
<param name="destination_port" value="17008" />
|
||||
<param name="destination_port" value="17012" />
|
||||
<rosparam param="topics">
|
||||
[{name: "/cameras/end_effector/image_256x144/compressed", compress: false, rate: 30.0}]
|
||||
</rosparam>
|
||||
|
||||
Reference in New Issue
Block a user