Added 2017-2018 mars rover repository.

This commit is contained in:
2018-08-22 14:54:52 -07:00
parent a56690ca18
commit 7fd2641766
750 changed files with 2019222 additions and 0 deletions

View File

@@ -0,0 +1,209 @@
cmake_minimum_required(VERSION 2.8.3)
project(rover_control)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
rospy
std_msgs
geometry_msgs
message_generation
)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a run_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
add_message_files(
FILES
DriveCommandMessage.msg
DriveControlMessage.msg
DriveStatusMessage.msg
IrisStatusMessage.msg
TowerPanTiltControlMessage.msg
MiningControlMessage.msg
MiningStatusMessage.msg
GripperControlMessage.msg
GripperStatusMessage.msg
CameraControlMessage.msg
)
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
std_msgs # Or other packages containing msgs
geometry_msgs
)
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES rover_control
# CATKIN_DEPENDS ros_msgs rospy
# DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
${catkin_INCLUDE_DIRS}
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/rover_control.cpp
# )
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/rover_control_node.cpp)
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
# ${catkin_LIBRARIES}
# )
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables and/or libraries for installation
# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_rover_control.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)

View File

@@ -0,0 +1,28 @@
<launch>
<group ns="rover_control">
<node name="iris_controller" pkg="rover_control" type="iris_controller.py" output="screen">
<param name="port" value="/dev/rover/ttyIRIS"/>
<param name="hertz" value="16"/>
</node>
<node name="control_coordinator" pkg="rover_control" type="control_coordinator.py" output="screen"/>
<node name="rear_bogie" pkg="rover_control" type="drive_control.py" output="screen">
<param name="port" value="/dev/rover/ttyBogieRear"/>
<param name="drive_control_topic" value="drive_control/rear"/>
</node>
<node name="left_bogie" pkg="rover_control" type="drive_control.py" output="screen">
<param name="port" value="/dev/rover/ttyBogieLeft"/>
<param name="drive_control_topic" value="drive_control/left"/>
<param name="invert_first_motor" value="True"/>
<param name="invert_second_motor" value="True"/>
</node>
<node name="right_bogie" pkg="rover_control" type="drive_control.py" output="screen">
<param name="port" value="/dev/rover/ttyBogieRight"/>
<param name="drive_control_topic" value="drive_control/right"/>
</node>
</group>
</launch>

View File

@@ -0,0 +1,7 @@
uint8 camera_mode
bool zoom_in
bool zoom_out
bool full_zoom_in
bool full_zoom_out
bool shoot

View File

@@ -0,0 +1,3 @@
bool controller_present
bool ignore_drive_control
geometry_msgs/Twist drive_twist

View File

@@ -0,0 +1,7 @@
bool first_motor_direction
bool first_motor_sleep
uint16 first_motor_speed
bool second_motor_direction
bool second_motor_sleep
uint16 second_motor_speed

View File

@@ -0,0 +1,11 @@
bool first_motor_connected
bool second_motor_connected
float32 first_motor_current
float32 second_motor_current
bool first_motor_fault
bool second_motor_fault
float32 first_motor_temp
float32 second_motor_temp

View File

@@ -0,0 +1,7 @@
uint8 gripper_mode
int32 gripper_position_absolute
int16 gripper_position_relative
bool should_home
bool toggle_light

View File

@@ -0,0 +1,13 @@
uint16 pinch_position_raw
uint16 forefinger_position_raw
uint16 thumb_position_raw
uint16 middlefinger_position_raw
uint16 pinch_current
uint16 forefinger_current
uint16 thumb_current
uint16 middlefinger_current
bool light_on
uint8 current_mode
uint16 current_finger_position

View File

@@ -0,0 +1,2 @@
bool iris_connected
uint16 voltage_24v

View File

@@ -0,0 +1,10 @@
int32 lift_set_relative
int32 tilt_set_relative
uint16 lift_set_absolute
uint16 tilt_set_absolute
bool measure
bool tare
int16 cal_factor

View File

@@ -0,0 +1,4 @@
uint16 lift_position
uint16 tilt_position
uint16 measured_weight

View File

@@ -0,0 +1,4 @@
bool should_center
int16 relative_pan_adjustment
int16 relative_tilt_adjustment

View File

@@ -0,0 +1,65 @@
<?xml version="1.0"?>
<package format="2">
<name>rover_control</name>
<version>0.0.0</version>
<description>The rover_control package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="caperren@todo.todo">caperren</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/rover_control</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>ros_msgs</build_depend>
<build_depend>rospy</build_depend>
<build_export_depend>ros_msgs</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<exec_depend>ros_msgs</exec_depend>
<exec_depend>rospy</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>

View File

@@ -0,0 +1,164 @@
#!/usr/bin/env python
#####################################
# Imports
#####################################
# Python native imports
import rospy
from time import time, sleep
import serial.rs485
import minimalmodbus
from std_msgs.msg import UInt8, UInt16
# Custom Imports
from rover_control.msg import TowerPanTiltControlMessage
#####################################
# Global Variables
#####################################
NODE_NAME = "chassis_pan_tilt_control"
DEFAULT_PORT = "/dev/rover/ttyChassisPanTilt"
DEFAULT_BAUD = 115200
DEFAULT_INVERT = False
DEFAULT_PAN_TILT_CONTROL_TOPIC = "chassis/pan_tilt/control"
PAN_TILT_NODE_ID = 1
COMMUNICATIONS_TIMEOUT = 0.01 # Seconds
RX_DELAY = 0.01
TX_DELAY = 0.01
DEFAULT_HERTZ = 20
PAN_TILT_MODBUS_REGISTERS = {
"CENTER_ALL": 0,
"PAN_ADJUST_POSITIVE": 1,
"PAN_ADJUST_NEGATIVE": 2,
"TILT_ADJUST_POSITIVE": 3,
"TILT_ADJUST_NEGATIVE": 4
}
PAN_TILT_CONTROL_DEFAULT_MESSAGE = [
0, # No centering
0, # No pan positive adjustment
0, # No pan negative adjustment
0, # No tilt positive adjustment
0 # No tilt negative adjustement
]
NODE_LAST_SEEN_TIMEOUT = 2 # seconds
#####################################
# DriveControl Class Definition
#####################################
class ChassisPanTiltControl(object):
def __init__(self):
rospy.init_node(NODE_NAME)
self.port = rospy.get_param("~port", DEFAULT_PORT)
self.baud = rospy.get_param("~baud", DEFAULT_BAUD)
self.pan_tilt_node_id = rospy.get_param("~pan_tilt_node_id", PAN_TILT_NODE_ID)
self.pan_tilt_control_subscriber_topic = rospy.get_param("~pan_tilt_control_topic",
DEFAULT_PAN_TILT_CONTROL_TOPIC)
self.wait_time = 1.0 / rospy.get_param("~hertz", DEFAULT_HERTZ)
self.pan_tilt_node = None
self.tower_node = None
self.connect_to_pan_tilt_and_tower()
self.pan_tilt_control_subscriber = rospy.Subscriber(self.pan_tilt_control_subscriber_topic,
TowerPanTiltControlMessage,
self.pan_tilt_control_callback)
self.pan_tilt_control_message = None
self.new_pan_tilt_control_message = False
self.modbus_nodes_seen_time = time()
self.run()
def __setup_minimalmodbus_for_485(self):
self.pan_tilt_node.serial = serial.rs485.RS485(self.port, baudrate=self.baud, timeout=COMMUNICATIONS_TIMEOUT)
self.pan_tilt_node.serial.rs485_mode = serial.rs485.RS485Settings(rts_level_for_rx=1, rts_level_for_tx=0,
delay_before_rx=RX_DELAY,
delay_before_tx=TX_DELAY)
def run(self):
# self.send_startup_centering_command()
while not rospy.is_shutdown():
start_time = time()
try:
self.send_pan_tilt_control_message()
self.modbus_nodes_seen_time = time()
except Exception, error:
pass
# print "Error occurred:", error
if (time() - self.modbus_nodes_seen_time) > NODE_LAST_SEEN_TIMEOUT:
print "Chassis pan/tilt not seen for", NODE_LAST_SEEN_TIMEOUT, "seconds. Exiting."
return # Exit so respawn can take over
time_diff = time() - start_time
sleep(max(self.wait_time - time_diff, 0))
def connect_to_pan_tilt_and_tower(self):
self.pan_tilt_node = minimalmodbus.Instrument(self.port, int(self.pan_tilt_node_id))
self.__setup_minimalmodbus_for_485()
def send_startup_centering_command(self):
try:
registers = list(PAN_TILT_CONTROL_DEFAULT_MESSAGE)
registers[PAN_TILT_MODBUS_REGISTERS["CENTER_ALL"]] = 1
self.pan_tilt_node.write_registers(0, registers)
except:
pass
def send_pan_tilt_control_message(self):
if self.new_pan_tilt_control_message:
pan_tilt_control_message = self.pan_tilt_control_message # type: TowerPanTiltControlMessage
registers = list(PAN_TILT_CONTROL_DEFAULT_MESSAGE)
registers[PAN_TILT_MODBUS_REGISTERS["CENTER_ALL"]] = int(pan_tilt_control_message.should_center)
if pan_tilt_control_message.relative_pan_adjustment >= 0:
registers[
PAN_TILT_MODBUS_REGISTERS["PAN_ADJUST_POSITIVE"]] = pan_tilt_control_message.relative_pan_adjustment
else:
registers[PAN_TILT_MODBUS_REGISTERS[
"PAN_ADJUST_NEGATIVE"]] = -pan_tilt_control_message.relative_pan_adjustment
if pan_tilt_control_message.relative_tilt_adjustment >= 0:
registers[PAN_TILT_MODBUS_REGISTERS[
"TILT_ADJUST_POSITIVE"]] = pan_tilt_control_message.relative_tilt_adjustment
else:
registers[PAN_TILT_MODBUS_REGISTERS[
"TILT_ADJUST_NEGATIVE"]] = -pan_tilt_control_message.relative_tilt_adjustment
self.pan_tilt_node.write_registers(0, registers)
self.new_pan_tilt_control_message = False
else:
self.pan_tilt_node.write_registers(0, PAN_TILT_CONTROL_DEFAULT_MESSAGE)
def pan_tilt_control_callback(self, pan_tilt_control):
self.pan_tilt_control_message = pan_tilt_control
self.new_pan_tilt_control_message = True
if __name__ == "__main__":
ChassisPanTiltControl()

View File

@@ -0,0 +1,26 @@
#!/usr/bin/env python
import rospy
import time
from rover_control.msg import TowerPanTiltControlMessage
DEFAULT_TOWER_PAN_TILT_CONTROL_TOPIC = "chassis/pan_tilt/control"
rospy.init_node("chassis_pan_tilt_tester")
publisher = rospy.Publisher(DEFAULT_TOWER_PAN_TILT_CONTROL_TOPIC, TowerPanTiltControlMessage, queue_size=1)
time.sleep(2)
message = TowerPanTiltControlMessage()
message.should_center = 1
publisher.publish(message)
time.sleep(1)
message = TowerPanTiltControlMessage()
message.relative_pan_adjustment = -100
message.relative_tilt_adjustment = -500
publisher.publish(message)

View File

@@ -0,0 +1,147 @@
#!/usr/bin/env python
#####################################
# Imports
#####################################
# Python native imports
import rospy
from PyQt5 import QtCore
from time import time, sleep
# Custom Imports
from rover_control.msg import DriveCommandMessage, DriveControlMessage
#####################################
# Global Variables
#####################################
NODE_NAME = "drive_coordinator"
DEFAULT_IRIS_DRIVE_COMMAND_TOPIC = "command_control/iris_drive"
DEFAULT_GROUND_STATION_DRIVE_COMMAND_TOPIC = "command_control/ground_station_drive"
DEFAULT_REAR_BOGIE_TOPIC = "drive_control/rear"
DEFAULT_LEFT_BOGIE_TOPIC = "drive_control/left"
DEFAULT_RIGHT_BOGIE_TOPIC = "drive_control/right"
UINT16_MAX = 65535
DEFAULT_HERTZ = 30
WATCHDOG_TIMEOUT = 0.3
#####################################
# ControlCoordinator Class Definition
#####################################
class DriveCoordinator(object):
def __init__(self):
rospy.init_node(NODE_NAME)
self.iris_drive_command_topic = rospy.get_param("~iris_drive_command_topic", DEFAULT_IRIS_DRIVE_COMMAND_TOPIC)
self.ground_station_drive_command_topic = \
rospy.get_param("~ground_station_drive_command_topic", DEFAULT_GROUND_STATION_DRIVE_COMMAND_TOPIC)
self.rear_bogie_topic = rospy.get_param("~rear_bogie_control_topic", DEFAULT_REAR_BOGIE_TOPIC)
self.left_bogie_topic = rospy.get_param("~left_bogie_control_topic", DEFAULT_LEFT_BOGIE_TOPIC)
self.right_bogie_topic = rospy.get_param("~right_bogie_control_topic", DEFAULT_RIGHT_BOGIE_TOPIC)
self.wait_time = 1.0 / rospy.get_param("~hertz", DEFAULT_HERTZ)
# Drive data
self.drive_command_data = {
"iris": {
"message": DriveCommandMessage(),
"last_time": time()
},
"ground_station": {
"message": DriveCommandMessage(),
"last_time": time()
}
}
# ########## Class Variables ##########
self.iris_drive_command_subscriber = rospy.Subscriber(self.iris_drive_command_topic,
DriveCommandMessage,
self.iris_drive_command_callback)
self.ground_station_command_subscriber = rospy.Subscriber(self.ground_station_drive_command_topic,
DriveCommandMessage,
self.ground_station_drive_command_callback)
self.rear_bogie_publisher = rospy.Publisher(self.rear_bogie_topic, DriveControlMessage, queue_size=1)
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)
self.last_message_time = time()
# ########## Run the Class ##########
self.run()
def run(self):
while not rospy.is_shutdown():
start_time = time()
try:
self.process_drive_commands()
except Exception, error:
print "COORDINATOR: Error occurred:", error
time_diff = time() - start_time
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:
self.send_drive_control_command(self.drive_command_data["ground_station"])
def send_drive_control_command(self, drive_command_data):
if (time() - drive_command_data["last_time"]) > WATCHDOG_TIMEOUT:
drive_command = DriveCommandMessage()
else:
drive_command = drive_command_data["message"]
rear_drive = DriveControlMessage()
left_drive = DriveControlMessage()
right_drive = DriveControlMessage()
left = drive_command.drive_twist.linear.x - drive_command.drive_twist.angular.z
right = drive_command.drive_twist.linear.x + drive_command.drive_twist.angular.z
left_direction = 1 if left >= 0 else 0
rear_drive.first_motor_direction = left_direction
left_drive.first_motor_direction = left_direction
left_drive.second_motor_direction = left_direction
right_direction = 1 if right >= 0 else 0
rear_drive.second_motor_direction = right_direction
right_drive.first_motor_direction = right_direction
right_drive.second_motor_direction = right_direction
left_speed = min(abs(left * UINT16_MAX), UINT16_MAX)
right_speed = min(abs(right * UINT16_MAX), UINT16_MAX)
rear_drive.first_motor_speed = left_speed
left_drive.first_motor_speed = left_speed
left_drive.second_motor_speed = left_speed
rear_drive.second_motor_speed = right_speed
right_drive.first_motor_speed = right_speed
right_drive.second_motor_speed = right_speed
self.rear_bogie_publisher.publish(rear_drive)
self.left_bogie_publisher.publish(left_drive)
self.right_bogie_publisher.publish(right_drive)
def iris_drive_command_callback(self, drive_command):
self.drive_command_data["iris"]["message"] = drive_command
self.drive_command_data["iris"]["last_time"] = time()
def ground_station_drive_command_callback(self, drive_command):
self.drive_command_data["ground_station"]["message"] = drive_command
self.drive_command_data["ground_station"]["last_time"] = time()
if __name__ == '__main__':
DriveCoordinator()

View File

@@ -0,0 +1,199 @@
#!/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, DriveStatusMessage
#####################################
# Global Variables
#####################################
NODE_NAME = "drive_control"
DEFAULT_PORT = "/dev/rover/ttyBogie"
DEFAULT_BAUD = 115200
DEFAULT_INVERT = False
DEFAULT_DRIVE_CONTROL_TOPIC = "drive_control/rear"
DEFAULT_DRIVE_CONTROL_STATUS_TOPIC = "drive_status/rear"
FIRST_MOTOR_ID = 1
SECOND_MOTOR_ID = 2
COMMUNICATIONS_TIMEOUT = 0.01 # Seconds
RX_DELAY = 0.01
TX_DELAY = 0.01
DEFAULT_HERTZ = 30
MODBUS_REGISTERS = {
"DIRECTION": 0,
"SPEED": 1,
"SLEEP": 2,
"CURRENT": 3,
"FAULT": 4,
"TEMPERATURE": 5
}
MOTOR_DRIVER_DEFAULT_MESSAGE = [
1, # Forwards
0, # 0 Speed
1 # Not in sleep mode
]
UINT16_MAX = 65535
BOGIE_LAST_SEEN_TIMEOUT = 2 # seconds
#####################################
# DriveControl Class Definition
#####################################
class DriveControl(object):
def __init__(self):
rospy.init_node(NODE_NAME)
self.port = rospy.get_param("~port", DEFAULT_PORT)
self.baud = rospy.get_param("~baud", DEFAULT_BAUD)
print self.port
self.first_motor_id = rospy.get_param("~first_motor_id", FIRST_MOTOR_ID)
self.second_motor_id = rospy.get_param("~second_motor_id", SECOND_MOTOR_ID)
self.first_motor_inverted = rospy.get_param("~invert_first_motor", DEFAULT_INVERT)
self.second_motor_inverted = rospy.get_param("~invert_second_motor", DEFAULT_INVERT)
self.drive_control_subscriber_topic = rospy.get_param("~drive_control_topic", DEFAULT_DRIVE_CONTROL_TOPIC)
self.drive_control_status_topic = rospy.get_param("~drive_control_status_topic", DEFAULT_DRIVE_CONTROL_STATUS_TOPIC)
self.wait_time = 1.0 / rospy.get_param("~hertz", DEFAULT_HERTZ)
self.first_motor = None
self.second_motor = None
self.connect_to_bogie()
self.drive_control_subscriber = \
rospy.Subscriber(self.drive_control_subscriber_topic, DriveControlMessage, self.drive_control_callback)
self.drive_control_status_publisher = rospy.Publisher(self.drive_control_status_topic, DriveStatusMessage, queue_size=1)
self.drive_control_message = DriveControlMessage()
self.new_control_message = False
self.bogie_last_seen = time()
self.run()
def __setup_minimalmodbus_for_485(self):
self.first_motor.serial = serial.rs485.RS485(self.port, baudrate=self.baud, timeout=COMMUNICATIONS_TIMEOUT)
self.first_motor.serial.rs485_mode = serial.rs485.RS485Settings(rts_level_for_rx=1, rts_level_for_tx=0,
delay_before_rx=RX_DELAY,
delay_before_tx=TX_DELAY)
self.second_motor.serial = serial.rs485.RS485(self.port, baudrate=self.baud, timeout=COMMUNICATIONS_TIMEOUT)
self.second_motor.serial.rs485_mode = serial.rs485.RS485Settings(rts_level_for_rx=1, rts_level_for_tx=0,
delay_before_rx=RX_DELAY,
delay_before_tx=TX_DELAY)
def run(self):
while not rospy.is_shutdown():
start_time = time()
try:
self.send_drive_control_message()
self.get_drive_status()
except Exception, error:
pass
if (time() - self.bogie_last_seen) > BOGIE_LAST_SEEN_TIMEOUT:
print "Bogie not seen for", BOGIE_LAST_SEEN_TIMEOUT, "seconds. Exiting."
return # Exit so respawn can take over
time_diff = time() - start_time
sleep(max(self.wait_time - time_diff, 0))
def connect_to_bogie(self):
self.first_motor = minimalmodbus.Instrument(self.port, int(self.first_motor_id))
self.second_motor = minimalmodbus.Instrument(self.port, int(self.second_motor_id))
self.__setup_minimalmodbus_for_485()
def send_drive_control_message(self):
if self.new_control_message:
drive_control = self.drive_control_message
try:
first_motor_register_data = list(MOTOR_DRIVER_DEFAULT_MESSAGE)
first_direction = \
not drive_control.first_motor_direction if self.first_motor_inverted else drive_control.first_motor_direction
first_motor_register_data[MODBUS_REGISTERS["DIRECTION"]] = first_direction
first_motor_register_data[MODBUS_REGISTERS["SPEED"]] = min(drive_control.first_motor_speed, UINT16_MAX)
second_motor_register_data = list(MOTOR_DRIVER_DEFAULT_MESSAGE)
second_direction = not drive_control.second_motor_direction if self.second_motor_inverted else drive_control.second_motor_direction
second_motor_register_data[MODBUS_REGISTERS["DIRECTION"]] = second_direction
second_motor_register_data[MODBUS_REGISTERS["SPEED"]] = min(drive_control.second_motor_speed, UINT16_MAX)
self.first_motor.write_registers(0, first_motor_register_data)
self.second_motor.write_registers(0, second_motor_register_data)
except Exception, error:
pass
self.new_control_message = False
def get_drive_status(self):
status = DriveStatusMessage()
first_motor_status = [0, 0, 0]
second_motor_status = [0, 0, 0]
try:
first_motor_status = self.first_motor.read_registers(3, 3)
status.first_motor_connected = True
except Exception:
status.first_motor_connected = False
try:
second_motor_status = self.second_motor.read_registers(3, 3)
status.second_motor_connected = True
except Exception:
status.second_motor_connected = False
if status.first_motor_connected or status.second_motor_connected:
self.bogie_last_seen = time()
if status.first_motor_connected:
status.first_motor_current = first_motor_status[0] / 1000.0
status.first_motor_fault = first_motor_status[1]
status.first_motor_temp = first_motor_status[2] / 1000.0
if status.second_motor_connected:
status.second_motor_current = second_motor_status[0] / 1000.0
status.second_motor_fault = second_motor_status[1]
status.second_motor_temp = second_motor_status[2] / 1000.0
self.drive_control_status_publisher.publish(status)
def drive_control_callback(self, drive_control):
self.drive_control_message = drive_control
self.new_control_message = True
if __name__ == "__main__":
DriveControl()

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

@@ -0,0 +1,401 @@
#!/usr/bin/env python
#####################################
# Imports
#####################################
# Python native imports
import rospy
from time import time, sleep
import serial.rs485
import minimalmodbus
# from std_msgs.msg import UInt8, UInt16
# Custom Imports
from rover_control.msg import MiningControlMessage, MiningStatusMessage, GripperControlMessage, GripperStatusMessage, CameraControlMessage
#####################################
# Global Variables
#####################################
NODE_NAME = "effectors_control"
# ##### Communication Defines #####
DEFAULT_PORT = "/dev/rover/ttyEffectors"
# DEFAULT_PORT = "/dev/ttyUSB0"
DEFAULT_BAUD = 115200
GRIPPER_NODE_ID = 1
MINING_NODE_ID = 2
SCIENCE_NODE_ID = 3
GRIPPER_TIMEOUT = 0.5
MINING_TIMEOUT = 0.3
FAILED_GRIPPER_MODBUS_LIMIT = 20
FAILED_MINING_MODBUS_LIMIMT = 20
RX_DELAY = 0.01
TX_DELAY = 0.01
DEFAULT_HERTZ = 40
GRIPPER_CONTROL_SUBSCRIBER_TOPIC = "gripper/control"
GRIPPER_STATUS_PUBLISHER_TOPIC = "gripper/status"
MINING_CONTROL_SUBSCRIBER_TOPIC = "mining/control"
MINING_STATUS_PUBLISHER_TOPIC = "mining/status"
CAMERA_CONTROL_SUBSCRIBER_TOPIC = "camera/control"
# ##### Gripper Defines #####
GRIPPER_MODBUS_REGISTERS = {
"MODE": 0,
"FINGER_POSITION": 1,
"HOME": 2,
"LIGHT_STATE": 3,
"CURRENT_PINCH": 4,
"CURRENT_FOREFINGER": 5,
"CURRENT_THUMB": 6,
"CURRENT_MIDDLEFINGER": 7,
"POSITION_PINCH": 8,
"POSITION_FOREFINGER": 9,
"POSITION_THUMB": 10,
"POSITION_MIDDLEFINGER": 11,
"LIGHT_STATE_OUPUT": 12,
"MODE_OUTPUT": 13,
"FINGER_POSITION_OUTPUT": 14
}
GRIPPER_MODES = {
"NO_CHANGE": 0,
"NORMAL": 1,
"TWO_FINGER_PINCH": 2,
"WIDE ": 3,
"SCISSOR": 4
}
DEFAULT_GRIPPER_REGISTERS = [
0, # No change
0, # No positional update
0, # Do not home
0, # Light off
]
GRIPPER_UNIVERSAL_POSITION_MAX = 10000
# ##### Mining Defines #####
MINING_MODBUS_REGISTERS = {
"LIFT_SET_POSITIVE": 0,
"LIFT_SET_NEGATIVE": 1,
"TILT_SET_POSITIVE": 2,
"TILT_SET_NEGATIVE": 3,
"TILT_SET_ABSOLUTE": 4,
"LIFT_SET_ABSOLUTE": 5,
"MEASURE": 6,
"TARE": 7,
"CAL_FACTOR": 8,
"CHANGE_VIEW_MODE": 9,
"ZOOM_IN": 10,
"ZOOM_OUT": 11,
"FULL_ZOOM_IN": 12,
"FULL_ZOOM_OUT": 13,
"SHOOT": 14,
"CURRENT_POSITION_LIFT": 15,
"CURRENT_POSITION_TILT": 16,
"MEASURED_WEIGHT": 17
}
MINING_POSITIONAL_THRESHOLD = 20
# ##### Science Defines #####
# ##### Misc Defines #####
NODE_LAST_SEEN_TIMEOUT = 2 # seconds
UINT16_MAX = 65535
#####################################
# DriveControl Class Definition
#####################################
class EffectorsControl(object):
EFFECTORS = [
"GRIPPER",
"MINING"
]
def __init__(self):
rospy.init_node(NODE_NAME)
self.port = rospy.get_param("~port", DEFAULT_PORT)
self.baud = rospy.get_param("~baud", DEFAULT_BAUD)
self.gripper_node_id = rospy.get_param("~gripper_node_id", GRIPPER_NODE_ID)
self.mining_node_id = rospy.get_param("~mining_node_id", MINING_NODE_ID)
self.gripper_control_subscriber_topic = rospy.get_param("~gripper_control_subscriber_topic",
GRIPPER_CONTROL_SUBSCRIBER_TOPIC)
self.gripper_status_publisher_topic = rospy.get_param("~gripper_status_publisher_topic",
GRIPPER_STATUS_PUBLISHER_TOPIC)
self.mining_control_subscriber_topic = rospy.get_param("~mining_control_subscriber_topic",
MINING_CONTROL_SUBSCRIBER_TOPIC)
self.mining_status_publisher_topic = rospy.get_param("~mining_status_publisher_topic",
MINING_STATUS_PUBLISHER_TOPIC)
self.camera_control_subscriber_topic = rospy.get_param("~camera_control_subscriber_topic",
CAMERA_CONTROL_SUBSCRIBER_TOPIC)
self.wait_time = 1.0 / rospy.get_param("~hertz", DEFAULT_HERTZ)
self.gripper_node = None # type:minimalmodbus.Instrument
self.mining_node = None # type:minimalmodbus.Instrument
self.gripper_node_present = False
self.mining_node_present = True
self.connect_to_nodes()
# self.check_which_nodes_present()
# ##### Subscribers #####
self.gripper_control_subscriber = rospy.Subscriber(self.gripper_control_subscriber_topic, GripperControlMessage, self.gripper_control_message_received__callback)
self.mining_control_subscriber = rospy.Subscriber(self.mining_control_subscriber_topic, MiningControlMessage, self.mining_control_message_received__callback)
self.camera_control_subscriber = rospy.Subscriber(self.camera_control_subscriber_topic, CameraControlMessage, self.camera_control_message_received__callback)
# ##### Publishers #####
self.gripper_status_publisher = rospy.Publisher(self.gripper_status_publisher_topic, GripperStatusMessage, queue_size=1)
self.mining_status_publisher = rospy.Publisher(self.mining_status_publisher_topic, MiningStatusMessage, queue_size=1)
# ##### Misc #####
self.modbus_nodes_seen_time = time()
# ##### Mining Variables #####
self.mining_registers = [0 for _ in MINING_MODBUS_REGISTERS]
self.gripper_registers = None
self.mining_control_message = None # type:MiningControlMessage
self.new_mining_control_message = False
self.gripper_control_message = None
self.new_gripper_control_message = False
self.camera_control_message = None # type: CameraControlMessage
self.new_camera_control_message = False
self.failed_gripper_modbus_count = 0
self.failed_mining_modbus_count = 0
self.which_effector = self.EFFECTORS.index("GRIPPER")
self.run()
def __setup_minimalmodbus_for_485(self):
self.gripper_node.serial = serial.rs485.RS485(self.port, baudrate=self.baud, timeout=GRIPPER_TIMEOUT)
self.gripper_node.serial.rs485_mode = serial.rs485.RS485Settings(rts_level_for_rx=1, rts_level_for_tx=0,
delay_before_rx=RX_DELAY,
delay_before_tx=TX_DELAY)
self.mining_node.serial = serial.rs485.RS485(self.port, baudrate=self.baud, timeout=MINING_TIMEOUT)
self.mining_node.serial.rs485_mode = serial.rs485.RS485Settings(rts_level_for_rx=1, rts_level_for_tx=0,
delay_before_rx=RX_DELAY,
delay_before_tx=TX_DELAY)
def run(self):
while not rospy.is_shutdown():
if self.which_effector == self.EFFECTORS.index("GRIPPER"):
try:
self.run_arm()
self.failed_gripper_modbus_count = 0
except:
self.failed_gripper_modbus_count += 1
if self.failed_gripper_modbus_count == FAILED_GRIPPER_MODBUS_LIMIT:
print "Gripper not present. Trying mining."
self.which_effector = self.EFFECTORS.index("MINING")
elif self.which_effector == self.EFFECTORS.index("MINING"):
try:
self.run_mining()
self.failed_mining_modbus_count = 0
except Exception, e:
print e
self.failed_mining_modbus_count += 1
if self.failed_mining_modbus_count == FAILED_MINING_MODBUS_LIMIMT:
print "No effectors present. Exiting...."
return
def run_arm(self):
self.process_gripper_control_message()
self.send_gripper_status_message()
def run_mining(self):
self.process_mining_control_message()
self.send_mining_status_message()
self.process_camera_control_message()
def connect_to_nodes(self):
self.gripper_node = minimalmodbus.Instrument(self.port, int(self.gripper_node_id))
self.mining_node = minimalmodbus.Instrument(self.port, int(self.mining_node_id))
self.__setup_minimalmodbus_for_485()
def process_mining_control_message(self):
if self.new_mining_control_message and self.mining_node_present:
lift_set_relative = self.mining_control_message.lift_set_relative
tilt_set_relative = self.mining_control_message.tilt_set_relative
lift_set_absolute = self.mining_control_message.lift_set_absolute
tilt_set_absolute = self.mining_control_message.tilt_set_absolute
cal_factor = min(self.mining_control_message.cal_factor, UINT16_MAX)
measure = self.mining_control_message.measure
tare = self.mining_control_message.tare
if lift_set_absolute < 1024:
self.mining_registers[MINING_MODBUS_REGISTERS["LIFT_SET_ABSOLUTE"]] = lift_set_absolute
else:
if lift_set_relative >= 0:
self.mining_registers[MINING_MODBUS_REGISTERS["LIFT_SET_POSITIVE"]] = lift_set_relative
else:
self.mining_registers[MINING_MODBUS_REGISTERS["LIFT_SET_NEGATIVE"]] = -lift_set_relative
if tilt_set_absolute < 1024:
self.mining_registers[MINING_MODBUS_REGISTERS["TILT_SET_ABSOLUTE"]] = tilt_set_absolute
else:
if tilt_set_relative >= 0:
self.mining_registers[MINING_MODBUS_REGISTERS["TILT_SET_POSITIVE"]] = tilt_set_relative
else:
self.mining_registers[MINING_MODBUS_REGISTERS["TILT_SET_NEGATIVE"]] = -tilt_set_relative
if cal_factor > -1:
self.mining_registers[MINING_MODBUS_REGISTERS["CAL_FACTOR"]] = cal_factor
self.mining_registers[MINING_MODBUS_REGISTERS["MEASURE"]] = int(measure)
self.mining_registers[MINING_MODBUS_REGISTERS["TARE"]] = int(tare)
self.mining_node.write_registers(0, self.mining_registers)
self.modbus_nodes_seen_time = time()
self.new_mining_control_message = False
def process_camera_control_message(self):
if self.new_camera_control_message:
print self.camera_control_message
self.mining_registers[MINING_MODBUS_REGISTERS["LIFT_SET_ABSOLUTE"]] = 1024
self.mining_registers[MINING_MODBUS_REGISTERS["LIFT_SET_POSITIVE"]] = 0
self.mining_registers[MINING_MODBUS_REGISTERS["LIFT_SET_NEGATIVE"]] = 0
self.mining_registers[MINING_MODBUS_REGISTERS["TILT_SET_ABSOLUTE"]] = 1024
self.mining_registers[MINING_MODBUS_REGISTERS["TILT_SET_POSITIVE"]] = 0
self.mining_registers[MINING_MODBUS_REGISTERS["TILT_SET_NEGATIVE"]] = 0
self.mining_registers[MINING_MODBUS_REGISTERS["MEASURE"]] = 0
self.mining_registers[MINING_MODBUS_REGISTERS["TARE"]] = 0
self.mining_registers[MINING_MODBUS_REGISTERS["CHANGE_VIEW_MODE"]] = self.camera_control_message.camera_mode
self.mining_registers[MINING_MODBUS_REGISTERS["ZOOM_IN"]] = self.camera_control_message.zoom_in
self.mining_registers[MINING_MODBUS_REGISTERS["ZOOM_OUT"]] = self.camera_control_message.zoom_out
self.mining_registers[MINING_MODBUS_REGISTERS["FULL_ZOOM_IN"]] = self.camera_control_message.full_zoom_in
self.mining_registers[MINING_MODBUS_REGISTERS["FULL_ZOOM_OUT"]] = self.camera_control_message.full_zoom_out
self.mining_registers[MINING_MODBUS_REGISTERS["SHOOT"]] = self.camera_control_message.shoot
self.mining_node.write_registers(0, self.mining_registers)
self.modbus_nodes_seen_time = time()
self.new_camera_control_message = False
def send_mining_status_message(self):
if self.mining_node_present:
self.mining_registers = self.mining_node.read_registers(0, len(MINING_MODBUS_REGISTERS))
message = MiningStatusMessage()
message.lift_position = self.mining_registers[MINING_MODBUS_REGISTERS["CURRENT_POSITION_LIFT"]]
message.tilt_position = self.mining_registers[MINING_MODBUS_REGISTERS["CURRENT_POSITION_TILT"]]
message.measured_weight = self.mining_registers[MINING_MODBUS_REGISTERS["MEASURED_WEIGHT"]]
self.mining_status_publisher.publish(message)
self.modbus_nodes_seen_time = time()
def process_gripper_control_message(self):
if not self.gripper_registers:
self.gripper_registers = self.gripper_node.read_registers(0, len(GRIPPER_MODBUS_REGISTERS))
if self.new_gripper_control_message:
self.gripper_registers[GRIPPER_MODBUS_REGISTERS["MODE"]] = self.gripper_control_message.gripper_mode
if self.gripper_control_message.should_home:
self.gripper_registers[GRIPPER_MODBUS_REGISTERS["HOME"]] = 1
self.gripper_node.write_registers(0, self.gripper_registers)
self.gripper_node.write_registers(0, DEFAULT_GRIPPER_REGISTERS)
homing_complete = False
while not homing_complete:
self.gripper_registers = self.gripper_node.read_registers(0, len(GRIPPER_MODBUS_REGISTERS))
self.send_gripper_status_message()
if self.gripper_registers[GRIPPER_MODBUS_REGISTERS["FINGER_POSITION_OUTPUT"]] == 0:
homing_complete = True
self.gripper_registers = None
else:
if self.gripper_control_message.toggle_light:
self.gripper_registers[GRIPPER_MODBUS_REGISTERS["LIGHT_STATE"]] = 0 if self.gripper_registers[GRIPPER_MODBUS_REGISTERS["LIGHT_STATE"]] else 1
self.gripper_control_message.toggle_light = False
gripper_absolute = self.gripper_control_message.gripper_position_absolute
gripper_relative = self.gripper_control_message.gripper_position_relative
if -1 < gripper_absolute < UINT16_MAX:
self.gripper_registers[GRIPPER_MODBUS_REGISTERS["FINGER_POSITION"]] = min(max(gripper_absolute, 0), UINT16_MAX)
else:
new_position = self.gripper_registers[GRIPPER_MODBUS_REGISTERS["FINGER_POSITION"]] + gripper_relative
self.gripper_registers[GRIPPER_MODBUS_REGISTERS["FINGER_POSITION"]] = min(max(new_position, 0), UINT16_MAX)
self.gripper_node.write_registers(0, self.gripper_registers)
self.gripper_node.write_registers(0, DEFAULT_GRIPPER_REGISTERS)
self.gripper_control_message = None
self.new_gripper_control_message = False
def send_gripper_status_message(self):
registers = self.gripper_node.read_registers(0, len(GRIPPER_MODBUS_REGISTERS))
message = GripperStatusMessage()
message.pinch_position_raw = registers[GRIPPER_MODBUS_REGISTERS["POSITION_PINCH"]]
message.forefinger_position_raw = registers[GRIPPER_MODBUS_REGISTERS["POSITION_FOREFINGER"]]
message.thumb_position_raw = registers[GRIPPER_MODBUS_REGISTERS["POSITION_THUMB"]]
message.middlefinger_position_raw = registers[GRIPPER_MODBUS_REGISTERS["POSITION_MIDDLEFINGER"]]
message.pinch_current = registers[GRIPPER_MODBUS_REGISTERS["CURRENT_PINCH"]]
message.forefinger_current = registers[GRIPPER_MODBUS_REGISTERS["CURRENT_FOREFINGER"]]
message.thumb_current = registers[GRIPPER_MODBUS_REGISTERS["CURRENT_THUMB"]]
message.middlefinger_current = registers[GRIPPER_MODBUS_REGISTERS["CURRENT_MIDDLEFINGER"]]
message.light_on = registers[GRIPPER_MODBUS_REGISTERS["LIGHT_STATE_OUPUT"]]
message.current_mode = registers[GRIPPER_MODBUS_REGISTERS["MODE_OUTPUT"]]
message.current_finger_position = registers[GRIPPER_MODBUS_REGISTERS["FINGER_POSITION_OUTPUT"]]
self.gripper_status_publisher.publish(message)
def gripper_control_message_received__callback(self, control_message):
self.gripper_control_message = control_message
self.new_gripper_control_message = True
def mining_control_message_received__callback(self, control_message):
self.mining_control_message = control_message
self.new_mining_control_message = True
def camera_control_message_received__callback(self, control_message):
self.camera_control_message = control_message
self.new_camera_control_message = True
if __name__ == "__main__":
EffectorsControl()

View File

@@ -0,0 +1,35 @@
#!/usr/bin/env python
import rospy
import time
from rover_control.msg import CameraControlMessage
TOPIC = "/rover_control/camera/control"
rospy.init_node("effectors_tester")
publisher = rospy.Publisher(TOPIC, CameraControlMessage, queue_size=1)
time.sleep(2)
# message = CameraControlMessage()
# message.full_zoom_in = 1
# publisher.publish(message)
time.sleep(2)
message = CameraControlMessage()
message.shoot = 1
publisher.publish(message)
time.sleep(5)
# message = MiningControlMessage()
# message.lift_set = -200
# message.tilt_set = -100
# message.cal_factor = -1
#
# publisher.publish(message)
#
# time.sleep(2)

View File

@@ -0,0 +1,57 @@
#!/usr/bin/env python
#####################################
# Imports
#####################################
# Python native imports
import rospy
from time import time, sleep
import serial
from std_msgs.msg import Float64
#####################################
# Global Variables
#####################################
NODE_NAME = "effectors_control"
# ##### Communication Defines #####
DEFAULT_PORT = "/dev/rover/ttyScale"
# DEFAULT_PORT = "/dev/ttyUSB3"
DEFAULT_BAUD = 115200
DEFAULT_TOPIC = "scale/measurement"
CAL_FACTOR = 89500
#####################################
# DriveControl Class Definition
#####################################
class EmergencyScale(object):
def __init__(self):
rospy.init_node(NODE_NAME)
self.scale_serial = serial.Serial(port=DEFAULT_PORT, baudrate=DEFAULT_BAUD, timeout=200)
self.publisher = rospy.Publisher(DEFAULT_TOPIC, Float64, queue_size=1)
self.run()
def run(self):
sleep(.2)
self.scale_serial.write(str(CAL_FACTOR))
sleep(.2)
while not rospy.is_shutdown():
value = self.scale_serial.readline()
try:
message = Float64()
message.data = float(value)
self.publisher.publish(message)
except:
print "No data"
if __name__ == "__main__":
EmergencyScale()

View File

@@ -0,0 +1,181 @@
#!/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 DriveCommandMessage, IrisStatusMessage
#####################################
# Global Variables
#####################################
NODE_NAME = "iris_controller"
DEFAULT_PORT = "/dev/rover/ttyIRIS"
DEFAULT_BAUD = 115200
DEFAULT_DRIVE_COMMAND_TOPIC = "command_control/iris_drive"
DEFAULT_IRIS_STATUS_TOPIC = "iris_status"
DEFAULT_HERTZ = 10
COMMUNICATIONS_TIMEOUT = 0.15 # Seconds
MODBUS_ID = 1
RX_DELAY = 0.01
TX_DELAY = 0.01
SBUS_VALUES = {
"SBUS_MAX": 1811,
"SBUS_MID": 991,
"SBUS_MIN": 172,
"SBUS_RANGE": 820.0,
"SBUS_DEADZONE": 5
}
MODBUS_REGISTERS = {
"LEFT_STICK_Y_AXIS": 0,
"RIGHT_STICK_Y_AXIS": 1,
"RIGHT_STICK_X_AXIS": 2,
"LEFT_STICK_X_AXIS": 3,
"LEFT_POT": 4,
"S1_POT": 5,
"S2_POT": 6,
"RIGHT_POT": 7,
"SA_SWITCH": 8,
"SB_SWITCH": 9,
"SC_SWITCH": 10,
"SD_SWITCH": 11,
"SE_SWITCH": 12,
"SF_SWITCH": 13,
"SG_SWITCH": 14,
"SH_SWITCH": 15,
"VOLTAGE_24V": 16,
"VOLTAGE_5V": 17,
"USB_VOLTAGE_5V": 18,
"VOLTAGE_3V3": 19
}
REGISTER_STATE_MAPPING = {
"IGNORE_CONTROL": "SF_SWITCH",
"DRIVE_VS_ARM": "SE_SWITCH"
}
IRIS_LAST_SEEN_TIMEOUT = 1 # seconds
#####################################
# IrisController Class Definition
#####################################
class IrisController(object):
def __init__(self):
rospy.init_node(NODE_NAME)
self.port = rospy.get_param("~port", DEFAULT_PORT)
self.baud = rospy.get_param("~baud", DEFAULT_BAUD)
self.drive_command_publisher_topic = rospy.get_param("~drive_command_topic", DEFAULT_DRIVE_COMMAND_TOPIC)
self.iris_status_publisher_topic = rospy.get_param("~iris_status_topic", DEFAULT_IRIS_STATUS_TOPIC)
self.wait_time = 1.0 / rospy.get_param("~hertz", DEFAULT_HERTZ)
self.iris = minimalmodbus.Instrument(self.port, MODBUS_ID)
self.__setup_minimalmodbus_for_485()
self.drive_command_publisher = rospy.Publisher(self.drive_command_publisher_topic, DriveCommandMessage,
queue_size=1)
self.iris_status_publisher = rospy.Publisher(self.iris_status_publisher_topic, IrisStatusMessage,
queue_size=1)
self.registers = []
self.iris_connected = False
self.iris_last_seen_time = time()
self.run()
def __setup_minimalmodbus_for_485(self):
self.iris.serial = serial.rs485.RS485(self.port, baudrate=self.baud, timeout=COMMUNICATIONS_TIMEOUT)
self.iris.serial.rs485_mode = serial.rs485.RS485Settings(rts_level_for_rx=1, rts_level_for_tx=0,
delay_before_rx=RX_DELAY, delay_before_tx=TX_DELAY)
def run(self):
while not rospy.is_shutdown():
start_time = time()
try:
self.read_registers()
self.broadcast_drive_if_current_mode()
self.broadcast_arm_if_current_mode()
self.broadcast_iris_status()
except Exception, error:
print "IRIS: Error occurred:", error
if (time() - self.iris_last_seen_time) > IRIS_LAST_SEEN_TIMEOUT:
print "Iris not seen for", IRIS_LAST_SEEN_TIMEOUT, "seconds. Exiting."
return # Exit so respawn can take over
time_diff = time() - start_time
sleep(max(self.wait_time - time_diff, 0))
def read_registers(self):
try:
self.registers = self.iris.read_registers(0, len(MODBUS_REGISTERS))
self.iris_last_seen_time = time()
except Exception, error:
self.iris_connected = False
def broadcast_drive_if_current_mode(self):
if self.registers[MODBUS_REGISTERS[REGISTER_STATE_MAPPING["DRIVE_VS_ARM"]]] < SBUS_VALUES["SBUS_MID"]:
command = DriveCommandMessage()
left_y_axis = self.registers[MODBUS_REGISTERS["LEFT_STICK_Y_AXIS"]]
right_y_axis = self.registers[MODBUS_REGISTERS["RIGHT_STICK_Y_AXIS"]]
if left_y_axis == 0 and right_y_axis == 0:
command.controller_present = False
command.ignore_drive_control = True
command.drive_twist.linear.x = 0
command.drive_twist.angular.z = 0
else:
left = (left_y_axis - SBUS_VALUES["SBUS_MID"]) / SBUS_VALUES[
"SBUS_RANGE"]
right = (right_y_axis - SBUS_VALUES["SBUS_MID"]) / SBUS_VALUES[
"SBUS_RANGE"]
command.controller_present = True
command.ignore_drive_control = \
self.registers[MODBUS_REGISTERS[REGISTER_STATE_MAPPING["IGNORE_CONTROL"]]] > SBUS_VALUES["SBUS_MID"]
command.drive_twist.linear.x = (left + right) / 2.0
command.drive_twist.angular.z = (right - left) / 2.0
self.drive_command_publisher.publish(command)
def broadcast_arm_if_current_mode(self):
if self.registers[MODBUS_REGISTERS[REGISTER_STATE_MAPPING["DRIVE_VS_ARM"]]] > \
SBUS_VALUES["SBUS_MIN"] + SBUS_VALUES["SBUS_DEADZONE"]:
print "Arm"
def broadcast_iris_status(self):
status_message = IrisStatusMessage()
status_message.iris_connected = True
status_message.voltage_24v = self.registers[MODBUS_REGISTERS["VOLTAGE_24V"]]
self.iris_status_publisher.publish(status_message)
if __name__ == "__main__":
IrisController()

View File

@@ -0,0 +1,227 @@
#!/usr/bin/env python
#####################################
# Imports
#####################################
# Python native imports
import rospy
from time import time, sleep
import serial.rs485
import minimalmodbus
from std_msgs.msg import UInt8, UInt16
# Custom Imports
from rover_control.msg import TowerPanTiltControlMessage
#####################################
# Global Variables
#####################################
NODE_NAME = "pan_tilt_and_tower_control"
DEFAULT_PORT = "/dev/rover/ttyTowerAndPanTilt"
DEFAULT_BAUD = 115200
DEFAULT_INVERT = False
DEFAULT_TOWER_LIGHT_CONTROL_TOPIC = "tower/light/control"
DEFAULT_TOWER_CO2_STATUS_TOPIC = "tower/status/co2"
DEFAULT_PAN_TILT_CONTROL_TOPIC = "tower/pan_tilt/control"
TOWER_NODE_ID = 1
PAN_TILT_NODE_ID = 2
COMMUNICATIONS_TIMEOUT = 0.02 # Seconds
RX_DELAY = 0.02
TX_DELAY = 0.02
DEFAULT_HERTZ = 20
PAN_TILT_MODBUS_REGISTERS = {
"CENTER_ALL": 0,
"PAN_ADJUST_POSITIVE": 1,
"PAN_ADJUST_NEGATIVE": 2,
"TILT_ADJUST_POSITIVE": 3,
"TILT_ADJUST_NEGATIVE": 4
}
TOWER_MODBUS_REGISTERS = {
"LED_CONTROL": 0,
"CO2_READING_PPM": 1
}
PAN_TILT_CONTROL_DEFAULT_MESSAGE = [
0, # No centering
0, # No pan positive adjustment
0, # No pan negative adjustment
0, # No tilt positive adjustment
0 # No tilt negative adjustement
]
TOWER_LIGHT_STATES = {
"NO_CHANGE": 0,
"LIGHT_OFF": 1,
"LIGHT_FLASH": 2,
"LIGHT_MED": 3,
"LIGHT_HIGH": 4
}
TOWER_CONTROL_DEFAULT_MESSAGE = [
TOWER_LIGHT_STATES["LIGHT_OFF"] # Light off
]
NODE_LAST_SEEN_TIMEOUT = 2 # seconds
#####################################
# DriveControl Class Definition
#####################################
class TowerPanTiltControl(object):
def __init__(self):
rospy.init_node(NODE_NAME)
self.port = rospy.get_param("~port", DEFAULT_PORT)
self.baud = rospy.get_param("~baud", DEFAULT_BAUD)
self.tower_node_id = rospy.get_param("~tower_node_id", TOWER_NODE_ID)
self.pan_tilt_node_id = rospy.get_param("~pan_tilt_node_id", PAN_TILT_NODE_ID)
self.tower_light_control_subscriber_topic = rospy.get_param("~tower_light_control_topic",
DEFAULT_TOWER_LIGHT_CONTROL_TOPIC)
self.pan_tilt_control_subscriber_topic = rospy.get_param("~pan_tilt_control_topic",
DEFAULT_PAN_TILT_CONTROL_TOPIC)
self.tower_co2_publisher_topic = rospy.get_param("~tower_co2_status_topic",
DEFAULT_TOWER_CO2_STATUS_TOPIC)
self.wait_time = 1.0 / rospy.get_param("~hertz", DEFAULT_HERTZ)
self.pan_tilt_node = None
self.tower_node = None
self.connect_to_pan_tilt_and_tower()
self.pan_tilt_control_subscriber = rospy.Subscriber(self.pan_tilt_control_subscriber_topic,
TowerPanTiltControlMessage,
self.pan_tilt_control_callback)
self.tower_light_control_subscriber = rospy.Subscriber(self.tower_light_control_subscriber_topic, UInt8,
self.tower_light_control_callback)
self.tower_co2_publisher = rospy.Publisher(self.tower_co2_publisher_topic, UInt16, queue_size=1)
self.pan_tilt_control_message = None
self.tower_light_control_message = None
self.new_pan_tilt_control_message = False
self.new_tower_light_control_message = False
self.modbus_nodes_seen_time = time()
self.run()
def __setup_minimalmodbus_for_485(self):
self.pan_tilt_node.serial = serial.rs485.RS485(self.port, baudrate=self.baud, timeout=COMMUNICATIONS_TIMEOUT)
self.pan_tilt_node.serial.rs485_mode = serial.rs485.RS485Settings(rts_level_for_rx=1, rts_level_for_tx=0,
delay_before_rx=RX_DELAY,
delay_before_tx=TX_DELAY)
self.tower_node.serial = serial.rs485.RS485(self.port, baudrate=self.baud, timeout=COMMUNICATIONS_TIMEOUT)
self.tower_node.serial.rs485_mode = serial.rs485.RS485Settings(rts_level_for_rx=1, rts_level_for_tx=0,
delay_before_rx=RX_DELAY,
delay_before_tx=TX_DELAY)
def run(self):
self.send_startup_centering_and_lights_off_command()
while not rospy.is_shutdown():
start_time = time()
try:
self.send_pan_tilt_control_message()
self.modbus_nodes_seen_time = time()
except Exception, error:
pass
# print "Error occurred:", error
try:
self.send_tower_control_message()
self.broadcast_co2_reading_message()
self.modbus_nodes_seen_time = time()
except Exception, error:
pass
# print "Error occurred:", error
if (time() - self.modbus_nodes_seen_time) > NODE_LAST_SEEN_TIMEOUT:
print "Tower pan/tilt not seen for", NODE_LAST_SEEN_TIMEOUT, "seconds. Exiting."
return # Exit so respawn can take over
time_diff = time() - start_time
sleep(max(self.wait_time - time_diff, 0))
def connect_to_pan_tilt_and_tower(self):
self.tower_node = minimalmodbus.Instrument(self.port, int(self.tower_node_id))
self.pan_tilt_node = minimalmodbus.Instrument(self.port, int(self.pan_tilt_node_id))
self.__setup_minimalmodbus_for_485()
def send_startup_centering_and_lights_off_command(self):
try:
# registers = list(PAN_TILT_CONTROL_DEFAULT_MESSAGE)
# registers[PAN_TILT_MODBUS_REGISTERS["CENTER_ALL"]] = 1
# self.pan_tilt_node.write_registers(0, registers)
self.tower_node.write_register(0, TOWER_LIGHT_STATES["LIGHT_OFF"])
except:
pass
def send_pan_tilt_control_message(self):
if self.new_pan_tilt_control_message:
pan_tilt_control_message = self.pan_tilt_control_message # type: TowerPanTiltControlMessage
registers = list(PAN_TILT_CONTROL_DEFAULT_MESSAGE)
registers[PAN_TILT_MODBUS_REGISTERS["CENTER_ALL"]] = int(pan_tilt_control_message.should_center)
if pan_tilt_control_message.relative_pan_adjustment >= 0:
registers[
PAN_TILT_MODBUS_REGISTERS["PAN_ADJUST_POSITIVE"]] = pan_tilt_control_message.relative_pan_adjustment
else:
registers[PAN_TILT_MODBUS_REGISTERS[
"PAN_ADJUST_NEGATIVE"]] = -pan_tilt_control_message.relative_pan_adjustment
if pan_tilt_control_message.relative_tilt_adjustment >= 0:
registers[PAN_TILT_MODBUS_REGISTERS[
"TILT_ADJUST_POSITIVE"]] = pan_tilt_control_message.relative_tilt_adjustment
else:
registers[PAN_TILT_MODBUS_REGISTERS[
"TILT_ADJUST_NEGATIVE"]] = -pan_tilt_control_message.relative_tilt_adjustment
self.pan_tilt_node.write_registers(0, registers)
self.new_pan_tilt_control_message = False
else:
self.pan_tilt_node.write_registers(0, PAN_TILT_CONTROL_DEFAULT_MESSAGE)
def broadcast_co2_reading_message(self):
self.tower_co2_publisher.publish(UInt16(data=self.tower_node.read_register(1)))
def send_tower_control_message(self):
if self.new_tower_light_control_message:
self.tower_node.write_register(0, self.tower_light_control_message.data)
self.new_tower_light_control_message = False
def pan_tilt_control_callback(self, pan_tilt_control):
self.pan_tilt_control_message = pan_tilt_control
self.new_pan_tilt_control_message = True
def tower_light_control_callback(self, light_control):
self.tower_light_control_message = light_control
self.new_tower_light_control_message = True
if __name__ == "__main__":
TowerPanTiltControl()

View File

@@ -0,0 +1,26 @@
#!/usr/bin/env python
import rospy
import time
from rover_control.msg import TowerPanTiltControlMessage
DEFAULT_TOWER_PAN_TILT_CONTROL_TOPIC = "tower/control"
rospy.init_node("tower_pan_tilt_tester")
publisher = rospy.Publisher(DEFAULT_TOWER_PAN_TILT_CONTROL_TOPIC, TowerPanTiltControlMessage, queue_size=1)
time.sleep(2)
message = TowerPanTiltControlMessage()
message.should_center = 1
publisher.publish(message)
time.sleep(1)
message = TowerPanTiltControlMessage()
message.relative_pan_adjustment = -100
message.relative_tilt_adjustment = -500
publisher.publish(message)