Back to defaults after OMSI. IRIS fully working again.

This commit is contained in:
2018-06-29 17:26:31 -07:00
parent 1a29881d5e
commit 8a83b6f140
4 changed files with 61 additions and 24 deletions

View File

@@ -1,15 +1,16 @@
# Examples
#########################
# SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="FTU9EU0I", ENV{ID_USB_INTERFACE_NUM}=="00", SYMLINK+="rover/ttyDEV0"
# SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="FTU9EU0I", ENV{ID_USB_INTERFACE_NUM}=="01", SYMLINK+="rover/ttyDEV1"
# SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="FTU9EU0I", ENV{ID_USB_INTERFACE_NUM}=="02", SYMLINK+="rover/ttyCompass"
# 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}=="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"
# IRIS Board Mappings
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2CZLZF", ENV{ID_USB_INTERFACE_NUM}=="00", SYMLINK+="rover/ttyREAR"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2CZLZF", ENV{ID_USB_INTERFACE_NUM}=="01", SYMLINK+="rover/ttyLEFT"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{serial}=="NM2CZLZF", ENV{ID_USB_INTERFACE_NUM}=="02", SYMLINK+="rover/ttyRIGHT"
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}=="NM2HPA6V", ENV{ID_USB_INTERFACE_NUM}=="00", SYMLINK+="rover/ttyIRIS_1_0"
@@ -22,6 +23,8 @@ SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6011", ATTRS{seria
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"
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6001", ATTRS{serial}=="A906H7P0", SYMLINK+="rover/ttyREAR"
##### Mappings from OMSI / EXPO driving with individual adapters
# 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"
# SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6001", ATTRS{serial}=="A906H7P0", SYMLINK+="rover/ttyREAR"

View File

@@ -0,0 +1,34 @@
#!/usr/bin/env python
#####################################
# Imports
#####################################
# Python native imports
import rospy
from time import time, sleep
import serial.rs485
import minimalmodbus
# Custom Imports
from rover_control.msg import DriveControlMessage
rospy.init_node("tester")
pub = rospy.Publisher("/drive_control/rear", DriveControlMessage, queue_size=1)
sleep(1)
while True:
speed = int(input("Enter Speed: "))
message = DriveControlMessage()
message.first_motor_speed = speed
message.first_motor_direction = 1
message.second_motor_speed = speed
pub.publish(message)
sleep(1)

View File

@@ -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>

View File

@@ -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>
<!--&lt;!&ndash; Start Main Navigation Camera &ndash;&gt;-->
<!--<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>-->
<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>
<!--&lt;!&ndash; Start Chassis Camera &ndash;&gt;-->
<!--<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>-->
<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>
<!--&lt;!&ndash; Start End Effector Camera &ndash;&gt;-->
<!--<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>-->
<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>