mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-08 18:21:15 +00:00
IRIS is back. Still driving on backups. Made modifications for OMSI.
This commit is contained in:
@@ -7,20 +7,20 @@
|
||||
# SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="FTU9EU0I", ENV{ID_USB_INTERFACE_NUM}=="03", SYMLINK+="rover/ttyGPS"
|
||||
|
||||
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2NFZVA", ENV{ID_USB_INTERFACE_NUM}=="00", SYMLINK+="rover/ttyIRIS_0_0"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2NFZVA", ENV{ID_USB_INTERFACE_NUM}=="01", SYMLINK+="rover/ttyIRIS_0_1"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2NFZVA", ENV{ID_USB_INTERFACE_NUM}=="02", SYMLINK+="rover/ttyIRIS_0_2"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2NFZVA", ENV{ID_USB_INTERFACE_NUM}=="03", SYMLINK+="rover/ttyIRIS_0_3"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2CZLZF", ENV{ID_USB_INTERFACE_NUM}=="00", SYMLINK+="rover/ttyIRIS_0_0"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2CZLZF", ENV{ID_USB_INTERFACE_NUM}=="01", SYMLINK+="rover/ttyIRIS_0_1"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2CZLZF", ENV{ID_USB_INTERFACE_NUM}=="02", SYMLINK+="rover/ttyIRIS_0_2"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2CZLZF", ENV{ID_USB_INTERFACE_NUM}=="03", SYMLINK+="rover/ttyIRIS_0_3"
|
||||
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2RJ8G5", ENV{ID_USB_INTERFACE_NUM}=="00", SYMLINK+="rover/ttyIRIS_1_0"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2RJ8G5", ENV{ID_USB_INTERFACE_NUM}=="01", SYMLINK+="rover/ttyIRIS_1_1"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2RJ8G5", ENV{ID_USB_INTERFACE_NUM}=="02", SYMLINK+="rover/ttyIRIS_1_2"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2RJ8G5", ENV{ID_USB_INTERFACE_NUM}=="03", SYMLINK+="rover/ttyIRIS_1_3"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2HPA6V", ENV{ID_USB_INTERFACE_NUM}=="00", SYMLINK+="rover/ttyIRIS_1_0"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2HPA6V", ENV{ID_USB_INTERFACE_NUM}=="01", SYMLINK+="rover/ttyIRIS_1_1"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2HPA6V", ENV{ID_USB_INTERFACE_NUM}=="02", SYMLINK+="rover/ttyIRIS_1_2"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2HPA6V", ENV{ID_USB_INTERFACE_NUM}=="03", SYMLINK+="rover/ttyIRIS_1_3"
|
||||
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2UFVE1", ENV{ID_USB_INTERFACE_NUM}=="00", SYMLINK+="rover/ttyIRIS_2_0"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2UFVE1", ENV{ID_USB_INTERFACE_NUM}=="01", SYMLINK+="rover/ttyIRIS_2_1"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2UFVE1", ENV{ID_USB_INTERFACE_NUM}=="02", SYMLINK+="rover/ttyIRIS_2_2"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2UFVE1", ENV{ID_USB_INTERFACE_NUM}=="03", SYMLINK+="rover/ttyIRIS_2_3"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM34WE0R", ENV{ID_USB_INTERFACE_NUM}=="00", SYMLINK+="rover/ttyIRIS_2_0"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM34WE0R", ENV{ID_USB_INTERFACE_NUM}=="01", SYMLINK+="rover/ttyIRIS_2_1"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM34WE0R", ENV{ID_USB_INTERFACE_NUM}=="02", SYMLINK+="rover/ttyIRIS"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM34WE0R", ENV{ID_USB_INTERFACE_NUM}=="03", SYMLINK+="rover/ttyIRIS_2_3"
|
||||
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6001", ATTRS{serial}=="AH05K2Y8", SYMLINK+="rover/ttyLEFT"
|
||||
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6001", ATTRS{serial}=="A906H89E", SYMLINK+="rover/ttyRIGHT"
|
||||
|
||||
@@ -91,9 +91,9 @@ class DriveCoordinator(object):
|
||||
sleep(max(self.wait_time - time_diff, 0))
|
||||
|
||||
def process_drive_commands(self):
|
||||
# if not self.drive_command_data["iris"]["message"].ignore_drive_control:
|
||||
# self.send_drive_control_command(self.drive_command_data["iris"])
|
||||
# else:
|
||||
if not self.drive_command_data["iris"]["message"].ignore_drive_control:
|
||||
self.send_drive_control_command(self.drive_command_data["iris"])
|
||||
else:
|
||||
self.send_drive_control_command(self.drive_command_data["ground_station"])
|
||||
|
||||
def send_drive_control_command(self, drive_command_data):
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
<include file="$(find rover_main)/launch/rover/status.launch"/>
|
||||
|
||||
<!-- ########## Start Nimbro Topic Transport Nodes ########## -->
|
||||
<include file="$(find rover_main)/launch/rover/topic_transport_senders.launch"/>
|
||||
<include file="$(find rover_main)/launch/rover/topic_transport_receivers.launch"/>
|
||||
<!--<include file="$(find rover_main)/launch/rover/topic_transport_senders.launch"/>-->
|
||||
<!--<include file="$(find rover_main)/launch/rover/topic_transport_receivers.launch"/>-->
|
||||
|
||||
</launch>
|
||||
|
||||
@@ -1,24 +1,24 @@
|
||||
<launch>
|
||||
<group ns="cameras">
|
||||
<!-- Start Undercarriage Camera -->
|
||||
<node name="undercarriage" pkg="rover_camera" type="rover_camera" launch-prefix="taskset -c 1" respawn="true" output="screen">
|
||||
<param name="device_path" value="/dev/rover/camera_undercarriage"/>
|
||||
</node>
|
||||
<!--<node name="undercarriage" pkg="rover_camera" type="rover_camera" launch-prefix="taskset -c 1" respawn="true" output="screen">-->
|
||||
<!--<param name="device_path" value="/dev/rover/camera_undercarriage"/>-->
|
||||
<!--</node>-->
|
||||
|
||||
<!-- Start Main Navigation Camera -->
|
||||
<node name="main_navigation" pkg="rover_camera" type="rover_camera" launch-prefix="taskset -c 2" respawn="true" output="screen" >
|
||||
<param name="device_path" value="/dev/rover/camera_main_navigation" />
|
||||
</node>
|
||||
<!--<!– Start Main Navigation Camera –>-->
|
||||
<!--<node name="main_navigation" pkg="rover_camera" type="rover_camera" launch-prefix="taskset -c 2" respawn="true" output="screen" >-->
|
||||
<!--<param name="device_path" value="/dev/rover/camera_main_navigation" />-->
|
||||
<!--</node>-->
|
||||
|
||||
<!-- Start Chassis Camera -->
|
||||
<node name="chassis" pkg="rover_camera" type="rover_camera" launch-prefix="taskset -c 3" respawn="true" output="screen" >
|
||||
<param name="device_path" value="/dev/rover/camera_chassis" />
|
||||
</node>
|
||||
<!--<!– Start Chassis Camera –>-->
|
||||
<!--<node name="chassis" pkg="rover_camera" type="rover_camera" launch-prefix="taskset -c 3" respawn="true" output="screen" >-->
|
||||
<!--<param name="device_path" value="/dev/rover/camera_chassis" />-->
|
||||
<!--</node>-->
|
||||
|
||||
<!-- Start End Effector Camera -->
|
||||
<node name="end_effector" pkg="rover_camera" type="rover_camera" launch-prefix="taskset -c 4" respawn="true" output="screen" >
|
||||
<param name="is_rtsp_camera" value="True" />
|
||||
<param name="device_path" value="rtsp://192.168.1.11" />
|
||||
</node>
|
||||
<!--<!– Start End Effector Camera –>-->
|
||||
<!--<node name="end_effector" pkg="rover_camera" type="rover_camera" launch-prefix="taskset -c 4" respawn="true" output="screen" >-->
|
||||
<!--<param name="is_rtsp_camera" value="True" />-->
|
||||
<!--<param name="device_path" value="rtsp://192.168.1.11" />-->
|
||||
<!--</node>-->
|
||||
</group>
|
||||
</launch>
|
||||
|
||||
@@ -1,16 +1,18 @@
|
||||
<launch>
|
||||
<group ns="rover_control">
|
||||
<!--<node name="iris_controller" pkg="rover_control" type="iris_controller.py" respawn="true" output="screen">-->
|
||||
<!--<param name="port" value="/dev/rover/ttyIRIS"/>-->
|
||||
<!--<param name="hertz" value="20"/>-->
|
||||
<!--</node>-->
|
||||
<node name="iris_controller" pkg="rover_control" type="iris_controller.py" respawn="true" output="screen">
|
||||
<param name="port" value="/dev/rover/ttyIRIS"/>
|
||||
<param name="hertz" value="20"/>
|
||||
</node>
|
||||
|
||||
<node name="rear_bogie" pkg="rover_control" type="drive_control.py" respawn="true" output="screen">
|
||||
<param name="port" value="/dev/rover/ttyREAR"/>
|
||||
<param name="drive_control_topic" value="drive_control/rear"/>
|
||||
<param name="drive_control_status_topic" value="drive_status/rear"/>
|
||||
<param name="first_motor_id" value="2"/>
|
||||
<param name="second_motor_id" value="1"/>
|
||||
<param name="first_motor_id" value="1"/>
|
||||
<param name="second_motor_id" value="2"/>
|
||||
<param name="invert_first_motor" value="True"/>
|
||||
<param name="invert_second_motor" value="True"/>
|
||||
</node>
|
||||
|
||||
<node name="left_bogie" pkg="rover_control" type="drive_control.py" respawn="true" output="screen">
|
||||
|
||||
Reference in New Issue
Block a user