mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-08 18:21:15 +00:00
MAJOR refactor of software layout. Needed as ground station and rover both need access to shared packages.
This commit is contained in:
201
software/ros_packages/rover_control/CMakeLists.txt
Normal file
201
software/ros_packages/rover_control/CMakeLists.txt
Normal file
@@ -0,0 +1,201 @@
|
||||
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
|
||||
)
|
||||
|
||||
## 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)
|
||||
@@ -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>
|
||||
@@ -0,0 +1,2 @@
|
||||
bool ignore_drive_control
|
||||
geometry_msgs/Twist drive_twist
|
||||
@@ -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
|
||||
65
software/ros_packages/rover_control/package.xml
Normal file
65
software/ros_packages/rover_control/package.xml
Normal 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>
|
||||
@@ -0,0 +1,90 @@
|
||||
#!/usr/bin/env python
|
||||
#####################################
|
||||
# Imports
|
||||
#####################################
|
||||
# Python native imports
|
||||
import rospy
|
||||
|
||||
from time import time, sleep
|
||||
|
||||
# Custom Imports
|
||||
from rover_control.msg import DriveCommandMessage, DriveControlMessage
|
||||
|
||||
#####################################
|
||||
# Global Variables
|
||||
#####################################
|
||||
NODE_NAME = "control_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
|
||||
|
||||
|
||||
#####################################
|
||||
# ControlCoordinator Class Definition
|
||||
#####################################
|
||||
class ControlCoordinator(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("~iris_drive_command_topic", DEFAULT_IRIS_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.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, )
|
||||
|
||||
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.run()
|
||||
|
||||
def run(self):
|
||||
while not rospy.is_shutdown():
|
||||
sleep(0.25)
|
||||
|
||||
def iris_drive_command_callback(self, drive_command):
|
||||
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)
|
||||
|
||||
if __name__ == "__main__":
|
||||
ControlCoordinator()
|
||||
@@ -0,0 +1,85 @@
|
||||
#!/usr/bin/env python
|
||||
#####################################
|
||||
# Imports
|
||||
#####################################
|
||||
# Python native imports
|
||||
import rospy
|
||||
|
||||
from time import time, sleep
|
||||
|
||||
# Custom Imports
|
||||
from rover_control.msg import DriveCommandMessage, DriveControlMessage
|
||||
|
||||
#####################################
|
||||
# Global Variables
|
||||
#####################################
|
||||
NODE_NAME = "control_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
|
||||
|
||||
|
||||
#####################################
|
||||
# ControlCoordinator Class Definition
|
||||
#####################################
|
||||
class DriveCoordinator(object):
|
||||
def __init__(self):
|
||||
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("~iris_drive_command_topic", DEFAULT_IRIS_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.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, )
|
||||
|
||||
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.run()
|
||||
|
||||
def run(self):
|
||||
while not rospy.is_shutdown():
|
||||
sleep(0.25)
|
||||
|
||||
def iris_drive_command_callback(self, drive_command):
|
||||
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)
|
||||
115
software/ros_packages/rover_control/src/drive_control/drive_control.py
Executable file
115
software/ros_packages/rover_control/src/drive_control/drive_control.py
Executable file
@@ -0,0 +1,115 @@
|
||||
#!/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
|
||||
|
||||
#####################################
|
||||
# Global Variables
|
||||
#####################################
|
||||
NODE_NAME = "drive_control"
|
||||
|
||||
DEFAULT_PORT = "/dev/rover/ttyBogie"
|
||||
DEFAULT_BAUD = 115200
|
||||
|
||||
DEFAULT_INVERT = False
|
||||
|
||||
DEFAULT_DRIVE_CONTROL_TOPIC = "drive_control/rear"
|
||||
|
||||
FIRST_MOTOR_ID = 1
|
||||
SECOND_MOTOR_ID = 2
|
||||
|
||||
COMMUNICATIONS_TIMEOUT = 0.15 # Seconds
|
||||
|
||||
RX_DELAY = 0.01
|
||||
TX_DELAY = 0.01
|
||||
|
||||
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
|
||||
|
||||
#####################################
|
||||
# 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)
|
||||
|
||||
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.first_motor = minimalmodbus.Instrument(self.port, FIRST_MOTOR_ID)
|
||||
self.second_motor = minimalmodbus.Instrument(self.port, SECOND_MOTOR_ID)
|
||||
self.__setup_minimalmodbus_for_485()
|
||||
|
||||
self.drive_control_subscriber = \
|
||||
rospy.Subscriber(self.drive_control_subscriber_topic, DriveControlMessage, self.drive_control_callback)
|
||||
|
||||
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():
|
||||
sleep(0.25)
|
||||
|
||||
def drive_control_callback(self, drive_control):
|
||||
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:
|
||||
print "Error occurred:", error
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
DriveControl()
|
||||
155
software/ros_packages/rover_control/src/iris_controller/iris_controller.py
Executable file
155
software/ros_packages/rover_control/src/iris_controller/iris_controller.py
Executable file
@@ -0,0 +1,155 @@
|
||||
#!/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
|
||||
|
||||
#####################################
|
||||
# Global Variables
|
||||
#####################################
|
||||
NODE_NAME = "iris_controller"
|
||||
|
||||
DEFAULT_PORT = "/dev/rover/ttyIRIS"
|
||||
DEFAULT_BAUD = 115200
|
||||
|
||||
DEFAULT_DRIVE_COMMAND_TOPIC = "command_control/iris_drive"
|
||||
|
||||
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"
|
||||
}
|
||||
|
||||
|
||||
#####################################
|
||||
# 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.wait_time = 1.0 / rospy.get_param("~hertz", DEFAULT_HERTZ)
|
||||
# print self.wait_time
|
||||
|
||||
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.registers = []
|
||||
|
||||
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()
|
||||
|
||||
except Exception, error:
|
||||
print "Error occurred:", error
|
||||
|
||||
time_diff = time() - start_time
|
||||
|
||||
sleep(max(self.wait_time - time_diff, 0))
|
||||
|
||||
def read_registers(self):
|
||||
self.registers = self.iris.read_registers(0, len(MODBUS_REGISTERS))
|
||||
|
||||
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.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.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"
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
IrisController()
|
||||
Reference in New Issue
Block a user