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,10 @@
# Rover Software
This code is what runs on the NUC onboard the Rover.
This handles everything from processing vision data to actually sending drive commands to the wheels.
## Requirements
* Python 3.X
* ROS (Version TBD)
## How to Launch
TBD

View File

@@ -0,0 +1,197 @@
cmake_minimum_required(VERSION 2.8.3)
project(ground_station)
## 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
)
## 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
# Message1.msg
# Message2.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
# )
################################################
## 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 ground_station
# CATKIN_DEPENDS 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}/ground_station.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/ground_station_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_ground_station.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,62 @@
<?xml version="1.0"?>
<package format="2">
<name>ground_station</name>
<version>0.0.0</version>
<description>The ground_station 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/ground_station</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>rospy</build_depend>
<build_export_depend>rospy</build_export_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,19 @@
#!/usr/bin/env bash
current_folder_name="scripts"
current_folder_name_length=`expr length $current_folder_name`
launch_dir="$( cd "$( dirname "${BASH_SOURCE[0]}" )" && pwd )"
launch_dir_length=`expr length $launch_dir`
launch_dir_length_without_current_folder=$(($launch_dir_length-$current_folder_name_length))
script_launch_path="${launch_dir:0:$launch_dir_length_without_current_folder}/src"
cd $script_launch_path
cp ~/key .
sleep 1
export DISPLAY=:0
python ground_station.py

View File

@@ -0,0 +1,295 @@
# coding=utf-8
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore, QtWidgets, QtGui
import logging
import rospy
from rover_arm.msg import ArmStatusMessage
from rover_control.msg import GripperStatusMessage
#####################################
# Global Variables
#####################################
ARM_STATUS_TOPIC = "/rover_arm/status"
GRIPPER_STATUS_TOPIC = "/rover_control/gripper/status"
COMMS_TO_STRING = {
0: "NO STATUS",
1: "COMMS OK",
2: "NO DEVICE",
4: "BUS ERROR",
8: "GEN COMM ERROR",
16: "PARAMETER ERROR",
32: "LENGTH ERROR"
}
TARGET_REACHED_BIT_POSITION = 1
STATUS_TO_STRING = {
1: "TARGET REACHED",
2: "ERROR RECOVERY",
3: "RUN",
4: "ENABLED",
5: "FAULT STOP",
6: "WARNING",
7: "STO ACTIVE",
8: "SERVO READY",
10: "BRAKING",
11: "HOMING",
12: "INITIALIZED",
13: "VOLT OK",
15: "PERMANENT STOP"
}
FAULT_TO_STRING = {
1: "TRACKING ERROR",
2: "OVER CURRENT",
# 3: "COMMUNICATION ERROR", # Was showing even though things were working???
4: "ENCODER FAILURE",
5: "OVER TEMP",
6: "UNDER VOLTAGE",
7: "OVER VOLTAGE",
8: "PROG OR MEM ERROR",
9: "HARDWARE ERROR",
10: "OVER VELOCITY",
11: "INIT ERROR",
12: "MOTION ERROR",
13: "RANGE ERROR",
14: "POWER STAGE FORCED OFF",
15: "HOST COMM ERROR"
}
GRIPPER_MODES = {
0: "No Change",
1: "Normal",
2: "Pinch",
3: "Wide ",
4: "Scissor"
}
#####################################
# Controller Class Definition
#####################################
class ArmIndication(QtCore.QObject):
base_position_updated__signal = QtCore.pyqtSignal(float)
shoulder_position_updated__signal = QtCore.pyqtSignal(float)
elbow_position_updated__signal = QtCore.pyqtSignal(float)
roll_position_updated__signal = QtCore.pyqtSignal(float)
wrist_pitch_position_updated__signal = QtCore.pyqtSignal(float)
wrist_roll_position_updated__signal = QtCore.pyqtSignal(float)
base_comms_state_update_ready__signal = QtCore.pyqtSignal(str)
shoulder_comms_state_update_ready__signal = QtCore.pyqtSignal(str)
elbow_comms_state_update_ready__signal = QtCore.pyqtSignal(str)
roll_comms_state_update_ready__signal = QtCore.pyqtSignal(str)
wrist_pitch_comms_state_update_ready__signal = QtCore.pyqtSignal(str)
wrist_roll_comms_state_update_ready__signal = QtCore.pyqtSignal(str)
base_status_update_ready__signal = QtCore.pyqtSignal(str)
shoulder_status_update_ready__signal = QtCore.pyqtSignal(str)
elbow_status_update_ready__signal = QtCore.pyqtSignal(str)
roll_status_update_ready__signal = QtCore.pyqtSignal(str)
wrist_pitch_status_update_ready__signal = QtCore.pyqtSignal(str)
wrist_roll_status_update_ready__signal = QtCore.pyqtSignal(str)
base_faults_update_ready__signal = QtCore.pyqtSignal(str)
shoulder_faults_update_ready__signal = QtCore.pyqtSignal(str)
elbow_faults_update_ready__signal = QtCore.pyqtSignal(str)
roll_faults_update_ready__signal = QtCore.pyqtSignal(str)
wrist_pitch_faults_update_ready__signal = QtCore.pyqtSignal(str)
wrist_roll_faults_update_ready__signal = QtCore.pyqtSignal(str)
pinch_position_updated__signal = QtCore.pyqtSignal(int)
forefinger_position_updated__signal = QtCore.pyqtSignal(int)
thumb_position_updated__signal = QtCore.pyqtSignal(int)
middlefinger_position_updated__signal = QtCore.pyqtSignal(int)
pinch_current_updated__signal = QtCore.pyqtSignal(int)
forefinger_current_updated__signal = QtCore.pyqtSignal(int)
thumb_current_updated__signal = QtCore.pyqtSignal(int)
middlefinger_current_updated__signal = QtCore.pyqtSignal(int)
gripper_reported_mode_updated__signal = QtCore.pyqtSignal(str)
gripper_reported_setpoint_updated__signal = QtCore.pyqtSignal(int)
def __init__(self, shared_objects):
super(ArmIndication, self).__init__()
# ########## Reference to class init variables ##########
self.shared_objects = shared_objects
self.right_screen = self.shared_objects["screens"]["right_screen"]
self.base_position_lcd_number = self.right_screen.base_position_lcd_number # type: QtWidgets.QLCDNumber
self.shoulder_position_lcd_number = self.right_screen.shoulder_position_lcd_number # type: QtWidgets.QLCDNumber
self.elbow_position_lcd_number = self.right_screen.elbow_position_lcd_number # type: QtWidgets.QLCDNumber
self.roll_position_lcd_number = self.right_screen.roll_position_lcd_number # type: QtWidgets.QLCDNumber
self.wrist_pitch_position_lcd_number = self.right_screen.wrist_pitch_position_lcd_number # type: QtWidgets.QLCDNumber
self.wrist_roll_position_lcd_number = self.right_screen.wrist_roll_position_lcd_number # type: QtWidgets.QLCDNumber
self.pinch_position_lcd_number = self.right_screen.pinch_position_lcd_number # type: QtWidgets.QLCDNumber
self.forefinger_position_lcd_number = self.right_screen.forefinger_position_lcd_number # type: QtWidgets.QLCDNumber
self.thumb_position_lcd_number = self.right_screen.thumb_position_lcd_number # type: QtWidgets.QLCDNumber
self.middlefinger_position_lcd_number = self.right_screen.middlefinger_position_lcd_number # type: QtWidgets.QLCDNumber
self.pinch_current_lcd_number = self.right_screen.pinch_current_lcd_number # type: QtWidgets.QLCDNumber
self.forefinger_current_lcd_number = self.right_screen.forefinger_current_lcd_number # type: QtWidgets.QLCDNumber
self.thumb_current_lcd_number = self.right_screen.thumb_current_lcd_number # type: QtWidgets.QLCDNumber
self.middlefinger_current_lcd_number = self.right_screen.middlefinger_current_lcd_number # type: QtWidgets.QLCDNumber
self.arm_controls_base_comms_label = self.right_screen.arm_controls_base_comms_label # type:QtWidgets.QLabel
self.arm_controls_base_status_label = self.right_screen.arm_controls_base_status_label # type:QtWidgets.QLabel
self.arm_controls_base_faults_label = self.right_screen.arm_controls_base_faults_label # type:QtWidgets.QLabel
self.arm_controls_shoulder_comms_label = self.right_screen.arm_controls_shoulder_comms_label # type:QtWidgets.QLabel
self.arm_controls_shoulder_status_label = self.right_screen.arm_controls_shoulder_status_label # type:QtWidgets.QLabel
self.arm_controls_shoulder_faults_label = self.right_screen.arm_controls_shoulder_faults_label # type:QtWidgets.QLabel
self.arm_controls_elbow_comms_label = self.right_screen.arm_controls_elbow_comms_label # type:QtWidgets.QLabel
self.arm_controls_elbow_status_label = self.right_screen.arm_controls_elbow_status_label # type:QtWidgets.QLabel
self.arm_controls_elbow_faults_label = self.right_screen.arm_controls_elbow_faults_label # type:QtWidgets.QLabel
self.arm_controls_roll_comms_label = self.right_screen.arm_controls_roll_comms_label # type:QtWidgets.QLabel
self.arm_controls_roll_status_label = self.right_screen.arm_controls_roll_status_label # type:QtWidgets.QLabel
self.arm_controls_roll_faults_label = self.right_screen.arm_controls_roll_faults_label # type:QtWidgets.QLabel
self.arm_controls_wrist_pitch_comms_label = self.right_screen.arm_controls_wrist_pitch_comms_label # type:QtWidgets.QLabel
self.arm_controls_wrist_pitch_status_label = self.right_screen.arm_controls_wrist_pitch_status_label # type:QtWidgets.QLabel
self.arm_controls_wrist_pitch_faults_label = self.right_screen.arm_controls_wrist_pitch_faults_label # type:QtWidgets.QLabel
self.arm_controls_wrist_roll_comms_label = self.right_screen.arm_controls_wrist_roll_comms_label # type:QtWidgets.QLabel
self.arm_controls_wrist_roll_status_label = self.right_screen.arm_controls_wrist_roll_status_label # type:QtWidgets.QLabel
self.arm_controls_wrist_roll_faults_label = self.right_screen.arm_controls_wrist_roll_faults_label # type:QtWidgets.QLabel
self.gripper_reported_mode_label = self.right_screen.gripper_reported_mode_label # type:QtWidgets.QLabel
self.gripper_reported_setpoint_lcd_number = self.right_screen.gripper_reported_setpoint_lcd_number # type: QtWidgets.QLCDNumber
# ########## Get the settings instance ##########
self.settings = QtCore.QSettings()
# ########## Get the Pick And Plate instance of the logger ##########
self.logger = logging.getLogger("groundstation")
# ########## Class Variables ##########
self.arm_status_subscriber = rospy.Subscriber(ARM_STATUS_TOPIC, ArmStatusMessage, self.on_arm_status_update_received__callback)
self.gripper_status_subscriver = rospy.Subscriber(GRIPPER_STATUS_TOPIC, GripperStatusMessage, self.on_gripper_status_update_received__callback)
# ########## Connect Signals and Slots ##########
self.connect_signals_and_slots()
def connect_signals_and_slots(self):
self.base_position_updated__signal.connect(self.base_position_lcd_number.display)
self.shoulder_position_updated__signal.connect(self.shoulder_position_lcd_number.display)
self.elbow_position_updated__signal.connect(self.elbow_position_lcd_number.display)
self.roll_position_updated__signal.connect(self.roll_position_lcd_number.display)
self.wrist_pitch_position_updated__signal.connect(self.wrist_pitch_position_lcd_number.display)
self.wrist_roll_position_updated__signal.connect(self.wrist_roll_position_lcd_number.display)
self.base_comms_state_update_ready__signal.connect(self.arm_controls_base_comms_label.setText)
self.shoulder_comms_state_update_ready__signal.connect(self.arm_controls_shoulder_comms_label.setText)
self.elbow_comms_state_update_ready__signal.connect(self.arm_controls_elbow_comms_label.setText)
self.roll_comms_state_update_ready__signal.connect(self.arm_controls_roll_comms_label.setText)
self.wrist_pitch_comms_state_update_ready__signal.connect(self.arm_controls_wrist_pitch_comms_label.setText)
self.wrist_roll_comms_state_update_ready__signal.connect(self.arm_controls_wrist_roll_comms_label.setText)
self.base_status_update_ready__signal.connect(self.arm_controls_base_status_label.setText)
self.shoulder_status_update_ready__signal.connect(self.arm_controls_shoulder_status_label.setText)
self.elbow_status_update_ready__signal.connect(self.arm_controls_elbow_status_label.setText)
self.roll_status_update_ready__signal.connect(self.arm_controls_roll_status_label.setText)
self.wrist_pitch_status_update_ready__signal.connect(self.arm_controls_wrist_pitch_status_label.setText)
self.wrist_roll_status_update_ready__signal.connect(self.arm_controls_wrist_roll_status_label.setText)
self.base_faults_update_ready__signal.connect(self.arm_controls_base_faults_label.setText)
self.shoulder_faults_update_ready__signal.connect(self.arm_controls_shoulder_faults_label.setText)
self.elbow_faults_update_ready__signal.connect(self.arm_controls_elbow_faults_label.setText)
self.roll_faults_update_ready__signal.connect(self.arm_controls_roll_faults_label.setText)
self.wrist_pitch_faults_update_ready__signal.connect(self.arm_controls_wrist_pitch_faults_label.setText)
self.wrist_roll_faults_update_ready__signal.connect(self.arm_controls_wrist_roll_faults_label.setText)
self.pinch_position_updated__signal.connect(self.pinch_position_lcd_number.display)
self.forefinger_position_updated__signal.connect(self.forefinger_position_lcd_number.display)
self.thumb_position_updated__signal.connect(self.thumb_position_lcd_number.display)
self.middlefinger_position_updated__signal.connect(self.middlefinger_position_lcd_number.display)
self.pinch_current_updated__signal.connect(self.pinch_current_lcd_number.display)
self.forefinger_current_updated__signal.connect(self.forefinger_current_lcd_number.display)
self.thumb_current_updated__signal.connect(self.thumb_current_lcd_number.display)
self.middlefinger_current_updated__signal.connect(self.middlefinger_current_lcd_number.display)
self.gripper_reported_mode_updated__signal.connect(self.gripper_reported_mode_label.setText)
self.gripper_reported_setpoint_updated__signal.connect(self.gripper_reported_setpoint_lcd_number.display)
def on_arm_status_update_received__callback(self, data):
self.base_comms_state_update_ready__signal.emit(self.process_comms_to_string(data.base_comm_status))
self.shoulder_comms_state_update_ready__signal.emit(self.process_comms_to_string(data.shoulder_comm_status))
self.elbow_comms_state_update_ready__signal.emit(self.process_comms_to_string(data.elbow_comm_status))
self.roll_comms_state_update_ready__signal.emit(self.process_comms_to_string(data.roll_comm_status))
self.wrist_pitch_comms_state_update_ready__signal.emit(
self.process_comms_to_string(data.wrist_pitch_comm_status))
self.wrist_roll_comms_state_update_ready__signal.emit(self.process_comms_to_string(data.wrist_roll_comm_status))
self.base_status_update_ready__signal.emit(self.process_statuses_to_string(data.base_status))
self.shoulder_status_update_ready__signal.emit(self.process_statuses_to_string(data.shoulder_status))
self.elbow_status_update_ready__signal.emit(self.process_statuses_to_string(data.elbow_status))
self.roll_status_update_ready__signal.emit(self.process_statuses_to_string(data.roll_status))
self.wrist_pitch_status_update_ready__signal.emit(self.process_statuses_to_string(data.wrist_pitch_status))
self.wrist_roll_status_update_ready__signal.emit(self.process_statuses_to_string(data.wrist_roll_status))
self.base_faults_update_ready__signal.emit(self.process_faults_to_string(data.base_faults))
self.shoulder_faults_update_ready__signal.emit(self.process_faults_to_string(data.shoulder_faults))
self.elbow_faults_update_ready__signal.emit(self.process_faults_to_string(data.elbow_faults))
self.roll_faults_update_ready__signal.emit(self.process_faults_to_string(data.roll_faults))
self.wrist_pitch_faults_update_ready__signal.emit(self.process_faults_to_string(data.wrist_pitch_faults))
self.wrist_roll_faults_update_ready__signal.emit(self.process_faults_to_string(data.wrist_roll_faults))
self.base_position_updated__signal.emit(data.base)
self.shoulder_position_updated__signal.emit(data.shoulder)
self.elbow_position_updated__signal.emit(data.elbow)
self.roll_position_updated__signal.emit(data.roll)
self.wrist_pitch_position_updated__signal.emit(data.wrist_pitch)
self.wrist_roll_position_updated__signal.emit(data.wrist_roll)
def on_gripper_status_update_received__callback(self, data):
data = data # type: GripperStatusMessage
self.pinch_position_updated__signal.emit(data.pinch_position_raw)
self.forefinger_position_updated__signal.emit(data.forefinger_position_raw)
self.thumb_position_updated__signal.emit(data.thumb_position_raw)
self.middlefinger_position_updated__signal.emit(data.middlefinger_position_raw)
self.pinch_current_updated__signal.emit(data.pinch_current)
self.forefinger_current_updated__signal.emit(data.forefinger_current)
self.thumb_current_updated__signal.emit(data.thumb_current)
self.middlefinger_current_updated__signal.emit(data.middlefinger_current)
self.gripper_reported_mode_updated__signal.emit(GRIPPER_MODES[data.current_mode])
self.gripper_reported_setpoint_updated__signal.emit(data.current_finger_position)
@staticmethod
def process_faults_to_string(faults):
fault_output = ""
for bit_position in FAULT_TO_STRING:
if (1 << bit_position) & faults:
fault_output += FAULT_TO_STRING[bit_position] + "\n"
return fault_output[:-1]
@staticmethod
def process_statuses_to_string(statuses):
status_output = ""
for bit_position in STATUS_TO_STRING:
if (1 << bit_position) & statuses:
status_output += STATUS_TO_STRING[bit_position] + "\n"
return status_output[:-1]
@staticmethod
def process_comms_to_string(comms):
return COMMS_TO_STRING[comms] if comms in COMMS_TO_STRING else "UNKNOWN"

View File

@@ -0,0 +1,337 @@
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore, QtWidgets
import logging
from inputs import devices, GamePad
from time import time
import rospy
from rover_control.msg import DriveCommandMessage, TowerPanTiltControlMessage
#####################################
# Global Variables
#####################################
GAME_CONTROLLER_NAME = "Microsoft X-Box One S pad"
DEFAULT_DRIVE_COMMAND_TOPIC = "/rover_control/command_control/ground_station_drive"
DEFAULT_TOWER_PAN_TILT_COMMAND_TOPIC = "/rover_control/tower/pan_tilt/control"
DEFAULT_CHASSIS_PAN_TILT_COMMAND_TOPIC = "/rover_control/chassis/pan_tilt/control"
DRIVE_COMMAND_HERTZ = 20
STICK_DEADBAND = 3500
STICK_MAX = 32768.0
STICK_OFFSET = 0
THROTTLE_MIN = 0.05
PAUSE_STATE_CHANGE_TIME = 0.5
CAMERA_CHANGE_TIME = 0.2
GUI_ELEMENT_CHANGE_TIME = 0.2
CAMERA_TOGGLE_CHANGE_TIME = 0.35
TOWER_PAN_TILT_X_AXIS_SCALAR = 2
TOWER_PAN_TILT_Y_AXIS_SCALAR = 15
CHASSIS_PAN_TILT_X_AXIS_SCALAR = 15
CHASSIS_PAN_TILT_Y_AXIS_SCALAR = 15
#####################################
# Controller Class Definition
#####################################
class LogitechJoystick(QtCore.QThread):
def __init__(self):
super(LogitechJoystick, self).__init__()
# ########## Thread Flags ##########
self.run_thread_flag = True
self.setup_controller_flag = True
self.data_acquisition_and_broadcast_flag = True
self.controller_acquired = False
# ########## Class Variables ##########
self.gamepad = None # type: GamePad
self.controller_states = {
"left_x_axis": 0,
"left_y_axis": 0,
"right_x_axis": 0,
"right_y_axis": 0,
"left_trigger": 0,
"right_trigger": 0,
"left_stick": 0,
"right_right": 0,
"left_bumper": 0,
"right_bumper": 0,
"d_pad_x": 0,
"d_pad_y": 0,
"back": 0,
"start": 0,
"a": 0,
"x": 0,
"y": 0,
"b": 0,
}
self.raw_mapping_to_class_mapping = {
"ABS_X": "left_x_axis",
"ABS_Y": "left_y_axis",
"ABS_RX": "right_x_axis",
"ABS_RY": "right_y_axis",
"ABS_Z": "left_trigger",
"ABS_RZ": "right_trigger",
"BTN_THUMBL": "left_stick",
"BTN_THUMBR": "right_right",
"BTN_TL": "left_bumper",
"BTN_TR": "right_bumper",
"ABS_HAT0X": "d_pad_x",
"ABS_HAT0Y": "d_pad_y",
"BTN_SELECT": "back",
"BTN_START": "start",
"BTN_SOUTH": "a",
"BTN_NORTH": "x",
"BTN_WEST": "y",
"BTN_EAST": "b",
}
self.ready = False
self.start()
def run(self):
while self.run_thread_flag:
if self.setup_controller_flag:
self.controller_acquired = self.__setup_controller()
self.setup_controller_flag = False
if self.data_acquisition_and_broadcast_flag:
self.__get_controller_data()
def __setup_controller(self):
for device in devices.gamepads:
# print device
if device.name == GAME_CONTROLLER_NAME:
self.gamepad = device
return True
return False
def __get_controller_data(self):
if self.controller_acquired:
events = self.gamepad.read()
for event in events:
# print event.code, event.state
if event.code in self.raw_mapping_to_class_mapping:
self.controller_states[self.raw_mapping_to_class_mapping[event.code]] = event.state
self.ready = True
#####################################
# Controller Class Definition
#####################################
class DriveAndCameraControlSender(QtCore.QThread):
set_speed_limit__signal = QtCore.pyqtSignal(int)
set_left_drive_output__signal = QtCore.pyqtSignal(int)
set_right_drive_output__signal = QtCore.pyqtSignal(int)
change_gui_element_selection__signal = QtCore.pyqtSignal(int)
change_camera_selection__signal = QtCore.pyqtSignal(int)
toggle_selected_gui_camera__signal = QtCore.pyqtSignal()
def __init__(self, shared_objects):
super(DriveAndCameraControlSender, self).__init__()
# ########## Reference to class init variables ##########
self.shared_objects = shared_objects
self.video_coordinator = self.shared_objects["threaded_classes"]["Video Coordinator"]
self.right_screen = self.shared_objects["screens"]["right_screen"]
self.rover_speed_limit_slider = self.right_screen.rover_speed_limit_slider # type: QtWidgets.QSlider
self.left_drive_progress_bar = self.right_screen.left_drive_progress_bar # type: QtWidgets.QProgressBar
self.right_drive_progress_bar = self.right_screen.right_drive_progress_bar # type: QtWidgets.QProgressBar
# ########## Get the settings instance ##########
self.settings = QtCore.QSettings()
# ########## Get the Pick And Plate instance of the logger ##########
self.logger = logging.getLogger("groundstation")
# ########## Thread Flags ##########
self.run_thread_flag = True
self.joystick = LogitechJoystick()
# ########## Class Variables ##########
# Publishers
self.drive_command_publisher = rospy.Publisher(DEFAULT_DRIVE_COMMAND_TOPIC, DriveCommandMessage, queue_size=1)
self.tower_pan_tilt_command_publisher = rospy.Publisher(DEFAULT_TOWER_PAN_TILT_COMMAND_TOPIC,
TowerPanTiltControlMessage, queue_size=1)
self.chassis_pan_tilt_command_publisher = rospy.Publisher(DEFAULT_CHASSIS_PAN_TILT_COMMAND_TOPIC,
TowerPanTiltControlMessage, queue_size=1)
self.current_pan_tilt_selection = "no_pan_tilt"
self.last_hat_x_was_movement = False
self.last_hat_y_was_movement = False
self.wait_time = 1.0 / DRIVE_COMMAND_HERTZ
self.drive_paused = True
self.last_pause_state_time = time()
self.last_gui_element_change_time = time()
self.last_camera_change_time = time()
self.last_camera_toggle_time = time()
self.speed_limit = 0.5
def run(self):
self.logger.debug("Starting Joystick Thread")
while self.run_thread_flag:
start_time = time()
self.check_and_set_pause_state()
self.__update_and_publish()
time_diff = time() - start_time
self.msleep(max(int(self.wait_time - time_diff), 0))
self.logger.debug("Stopping Joystick Thread")
def connect_signals_and_slots(self):
self.set_left_drive_output__signal.connect(self.left_drive_progress_bar.setValue)
self.set_right_drive_output__signal.connect(self.right_drive_progress_bar.setValue)
self.video_coordinator.pan_tilt_selection_changed__signal.connect(self.on_pan_tilt_selection_changed__slot)
self.rover_speed_limit_slider.valueChanged.connect(self.on_speed_limit_slider_value_changed__slot)
def check_and_set_pause_state(self):
thumb_pressed = self.joystick.controller_states["start"]
if thumb_pressed and (time() - self.last_pause_state_time) > PAUSE_STATE_CHANGE_TIME:
self.drive_paused = not self.drive_paused
self.show_changed_pause_state()
self.last_pause_state_time = time()
def __update_and_publish(self):
self.publish_drive_command()
self.publish_camera_control_commands()
self.publish_pan_tilt_control_commands()
def publish_drive_command(self):
if self.drive_paused:
drive_message = DriveCommandMessage()
else:
drive_message = self.get_drive_message(self.speed_limit)
left_output = abs(drive_message.drive_twist.linear.x - drive_message.drive_twist.angular.z)
right_output = abs(drive_message.drive_twist.linear.x + drive_message.drive_twist.angular.z)
self.set_speed_limit__signal.emit(self.speed_limit * 100)
self.set_left_drive_output__signal.emit(left_output * 100)
self.set_right_drive_output__signal.emit(right_output * 100)
self.drive_command_publisher.publish(drive_message)
def publish_camera_control_commands(self):
trigger_pressed = self.joystick.controller_states["y"]
three_pressed = self.joystick.controller_states["left_bumper"]
four_pressed = self.joystick.controller_states["right_bumper"]
five_pressed = self.joystick.controller_states["left_trigger"]
six_pressed = self.joystick.controller_states["right_trigger"]
if (five_pressed or six_pressed) and (time() - self.last_camera_change_time) > CAMERA_CHANGE_TIME:
change = -1 if five_pressed else 1
self.change_camera_selection__signal.emit(change)
self.last_camera_change_time = time()
if (three_pressed or four_pressed) and (time() - self.last_gui_element_change_time) > GUI_ELEMENT_CHANGE_TIME:
change = -1 if three_pressed else 1
self.change_gui_element_selection__signal.emit(change)
self.last_gui_element_change_time = time()
if trigger_pressed and (time() - self.last_camera_toggle_time) > CAMERA_TOGGLE_CHANGE_TIME:
self.toggle_selected_gui_camera__signal.emit()
self.last_camera_toggle_time = time()
def publish_pan_tilt_control_commands(self):
button_eight = self.joystick.controller_states["a"]
hat_x = self.joystick.controller_states["d_pad_x"]
hat_y = self.joystick.controller_states["d_pad_y"]
if (hat_x == 0 and not self.last_hat_x_was_movement) and (
hat_y == 0 and not self.last_hat_y_was_movement) and not button_eight:
return
self.last_hat_x_was_movement = True if hat_x != 0 else False
self.last_hat_y_was_movement = True if hat_y != 0 else False
pan_tilt_message = TowerPanTiltControlMessage()
if button_eight:
pan_tilt_message.should_center = 1
if self.current_pan_tilt_selection == "tower_pan_tilt":
pan_tilt_message.relative_pan_adjustment = hat_x * TOWER_PAN_TILT_X_AXIS_SCALAR
pan_tilt_message.relative_tilt_adjustment = -(hat_y * TOWER_PAN_TILT_Y_AXIS_SCALAR)
self.tower_pan_tilt_command_publisher.publish(pan_tilt_message)
elif self.current_pan_tilt_selection == "chassis_pan_tilt":
pan_tilt_message.relative_pan_adjustment = hat_x * CHASSIS_PAN_TILT_X_AXIS_SCALAR
pan_tilt_message.relative_tilt_adjustment = -(hat_y * CHASSIS_PAN_TILT_Y_AXIS_SCALAR)
self.chassis_pan_tilt_command_publisher.publish(pan_tilt_message)
def get_drive_message(self, speed_limit):
drive_message = DriveCommandMessage()
left_y_axis = self.joystick.controller_states["left_y_axis"] if abs(self.joystick.controller_states["left_y_axis"]) > STICK_DEADBAND else 0
right_y_axis = self.joystick.controller_states["right_y_axis"] if abs(self.joystick.controller_states["right_y_axis"]) > STICK_DEADBAND else 0
left_y_axis = speed_limit * (-(left_y_axis - STICK_OFFSET) / STICK_MAX)
right_y_axis = speed_limit * (-(right_y_axis - STICK_OFFSET) / STICK_MAX)
drive_message.drive_twist.linear.x = (left_y_axis + right_y_axis) / 2.0
drive_message.drive_twist.angular.z = (right_y_axis - left_y_axis) / 2.0
return drive_message
def on_pan_tilt_selection_changed__slot(self, selection):
self.current_pan_tilt_selection = selection
def on_speed_limit_slider_value_changed__slot(self, value):
self.speed_limit = value / 100.0
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
start_signal.connect(self.start)
signals_and_slots_signal.connect(self.connect_signals_and_slots)
kill_signal.connect(self.on_kill_threads_requested__slot)
def show_changed_pause_state(self):
if self.drive_paused:
self.left_drive_progress_bar.setStyleSheet("background-color:darkred;")
self.right_drive_progress_bar.setStyleSheet("background-color:darkred;")
else:
self.left_drive_progress_bar.setStyleSheet("background-color: transparent;")
self.right_drive_progress_bar.setStyleSheet("background-color: transparent;")
def on_kill_threads_requested__slot(self):
self.run_thread_flag = False

View File

@@ -0,0 +1,445 @@
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore, QtWidgets
import logging
from inputs import devices, GamePad
from time import time
import rospy
from rover_arm.msg import ArmControlMessage
from rover_control.msg import MiningControlMessage, GripperControlMessage
#####################################
# Global Variables
#####################################
GAME_CONTROLLER_NAME = "Afterglow Gamepad for Xbox 360"
DRIVE_COMMAND_HERTZ = 20
GRIPPER_CONTROL_TOPIC = "/rover_control/gripper/control"
RELATIVE_ARM_CONTROL_TOPIC = "/rover_arm/control/relative"
MINING_CONTROL_TOPIC = "/rover_control/mining/control"
BASE_SCALAR = 0.003
SHOULDER_SCALAR = 0.002
ELBOW_SCALAR = 0.002
ROLL_SCALAR = 0.003
WRIST_PITCH_SCALAR = 0.003
WRIST_ROLL_SCALAR = 0.006
GRIPPER_MOVEMENT_SCALAR = 1500
LEFT_X_AXIS_DEADZONE = 1500
LEFT_Y_AXIS_DEADZONE = 1500
RIGHT_X_AXIS_DEADZONE = 1500
RIGHT_Y_AXIS_DEADZONE = 1500
THUMB_STICK_MAX = 32768.0
MINING_LIFT_SCALAR = 5
MINING_TILT_SCALAR = 5
COLOR_GREEN = "background-color:darkgreen; border: 1px solid black;"
COLOR_NONE = "border: 1px solid black;"
#####################################
# Controller Class Definition
#####################################
class XBOXController(QtCore.QThread):
def __init__(self):
super(XBOXController, self).__init__()
# ########## Thread Flags ##########
self.run_thread_flag = True
self.setup_controller_flag = True
self.data_acquisition_and_broadcast_flag = True
self.controller_acquired = False
# ########## Class Variables ##########
self.gamepad = None # type: GamePad
self.controller_states = {
"left_x_axis": 0,
"left_y_axis": 0,
"left_stick_button": 0,
"right_x_axis": 0,
"right_y_axis": 0,
"right_stick_button": 0,
"left_trigger": 0,
"left_bumper": 0,
"right_trigger": 0,
"right_bumper": 0,
"hat_x_axis": 0,
"hat_y_axis": 0,
"back_button": 0,
"start_button": 0,
"xbox_button": 0,
"x_button": 0,
"a_button": 0,
"b_button": 0,
"y_button": 0
}
self.raw_mapping_to_class_mapping = {
"ABS_X": "left_x_axis",
"ABS_Y": "left_y_axis",
"BTN_THUMBL": "left_stick_button",
"ABS_RX": "right_x_axis",
"ABS_RY": "right_y_axis",
"BTN_THUMBR": "right_stick_button",
"ABS_Z": "left_trigger",
"BTN_TL": "left_bumper",
"ABS_RZ": "right_trigger",
"BTN_TR": "right_bumper",
"ABS_HAT0X": "hat_x_axis",
"ABS_HAT0Y": "hat_y_axis",
"BTN_SELECT": "back_button",
"BTN_START": "start_button",
"BTN_MODE": "xbox_button",
"BTN_NORTH": "x_button",
"BTN_SOUTH": "a_button",
"BTN_EAST": "b_button",
"BTN_WEST": "y_button"
}
self.ready = False
self.start()
def run(self):
while self.run_thread_flag:
if self.setup_controller_flag:
self.controller_acquired = self.__setup_controller()
self.setup_controller_flag = False
if self.data_acquisition_and_broadcast_flag:
self.__get_controller_data()
def __setup_controller(self):
for device in devices.gamepads:
# print device
if device.name == GAME_CONTROLLER_NAME:
self.gamepad = device
return True
return False
def __get_controller_data(self):
if self.controller_acquired:
events = self.gamepad.read()
for event in events:
# For seeing codes you haven't added yet...
# if event.code not in self.raw_mapping_to_class_mapping and event.code != "SYN_REPORT":
# print event.code, ":", event.state
if event.code in self.raw_mapping_to_class_mapping:
# print event.code, ":", event.state
self.controller_states[self.raw_mapping_to_class_mapping[event.code]] = event.state
self.ready = True
#####################################
# Controller Class Definition
#####################################
class EffectorsAndArmControlSender(QtCore.QThread):
xbox_control_arm_stylesheet_update_ready__signal = QtCore.pyqtSignal(str)
xbox_control_mining_stylesheet_update_ready__signal = QtCore.pyqtSignal(str)
gripper_mode_normal_stylesheet_update_ready__signal = QtCore.pyqtSignal(str)
gripper_mode_pinch_stylesheet_update_ready__signal = QtCore.pyqtSignal(str)
gripper_mode_wide_stylesheet_update_ready__signal = QtCore.pyqtSignal(str)
gripper_mode_scissor_stylesheet_update_ready__signal = QtCore.pyqtSignal(str)
XBOX_CONTROL_STATES = [
"ARM",
"MINING"
]
GRIPPER_CONTROL_MODES = {
"NORMAL": 1,
"TWO_FINGER_PINCH": 2,
"WIDE": 3,
"SCISSOR": 4
}
PINCH_MODE_ABSOLUTE_SET_POSITION = 57740
def __init__(self, shared_objects):
super(EffectorsAndArmControlSender, self).__init__()
# ########## Reference to class init variables ##########
self.shared_objects = shared_objects
self.left_screen = self.shared_objects["screens"]["left_screen"]
self.right_screen = self.shared_objects["screens"]["right_screen"]
self.xbox_mode_arm_label = self.right_screen.xbox_mode_arm_label # type: QtWidgets.QLabel
self.xbox_mode_mining_label = self.right_screen.xbox_mode_mining_label # type: QtWidgets.QLabel
self.gripper_mode_normal_label = self.right_screen.gripper_mode_normal_label # type: QtWidgets.QLabel
self.gripper_mode_pinch_label = self.right_screen.gripper_mode_pinch_label # type: QtWidgets.QLabel
self.gripper_mode_wide_label = self.right_screen.gripper_mode_wide_label # type: QtWidgets.QLabel
self.gripper_mode_scissor_label = self.right_screen.gripper_mode_scissor_label # type: QtWidgets.QLabel
# ########## Get the settings instance ##########
self.settings = QtCore.QSettings()
# ########## Get the Pick And Plate instance of the logger ##########
self.logger = logging.getLogger("groundstation")
# ########## Thread Flags ##########
self.run_thread_flag = True
self.controller = XBOXController()
# ########## Class Variables ##########
self.wait_time = 1.0 / DRIVE_COMMAND_HERTZ
self.gripper_control_publisher = rospy.Publisher(GRIPPER_CONTROL_TOPIC, GripperControlMessage, queue_size=1)
self.relative_arm_control_publisher = rospy.Publisher(RELATIVE_ARM_CONTROL_TOPIC, ArmControlMessage,
queue_size=1)
self.mining_control_publisher = rospy.Publisher(MINING_CONTROL_TOPIC, MiningControlMessage, queue_size=1)
self.xbox_current_control_state = self.XBOX_CONTROL_STATES.index("ARM")
self.xbox_control_state_just_changed = False
self.last_xbox_button_state = 0
self.last_left_bumper_state = 0
self.last_right_bumper_state = 0
self.last_back_button_state = 0
self.gripper_control_mode = 1
self.gripper_control_mode_just_changed = False
self.send_new_gripper_mode = False
self.GRIPPER_DISPLAY_SIGNAL_MAPPING = {
self.GRIPPER_CONTROL_MODES["NORMAL"]: {
"SET": [self.gripper_mode_normal_stylesheet_update_ready__signal],
"UNSET": [self.gripper_mode_pinch_stylesheet_update_ready__signal,
self.gripper_mode_wide_stylesheet_update_ready__signal,
self.gripper_mode_scissor_stylesheet_update_ready__signal]
},
self.GRIPPER_CONTROL_MODES["TWO_FINGER_PINCH"]: {
"SET": [self.gripper_mode_pinch_stylesheet_update_ready__signal],
"UNSET": [self.gripper_mode_normal_stylesheet_update_ready__signal,
self.gripper_mode_wide_stylesheet_update_ready__signal,
self.gripper_mode_scissor_stylesheet_update_ready__signal]
},
self.GRIPPER_CONTROL_MODES["WIDE"]: {
"SET": [self.gripper_mode_wide_stylesheet_update_ready__signal],
"UNSET": [self.gripper_mode_pinch_stylesheet_update_ready__signal,
self.gripper_mode_normal_stylesheet_update_ready__signal,
self.gripper_mode_scissor_stylesheet_update_ready__signal]
},
self.GRIPPER_CONTROL_MODES["SCISSOR"]: {
"SET": [self.gripper_mode_scissor_stylesheet_update_ready__signal],
"UNSET": [self.gripper_mode_pinch_stylesheet_update_ready__signal,
self.gripper_mode_wide_stylesheet_update_ready__signal,
self.gripper_mode_normal_stylesheet_update_ready__signal],
# "ABS_MOVE": self.PINCH_MODE_ABSOLUTE_SET_POSITION
}
}
def run(self):
self.logger.debug("Starting Joystick Thread")
while self.run_thread_flag:
start_time = time()
self.change_control_state_if_needed()
if self.xbox_current_control_state == self.XBOX_CONTROL_STATES.index("ARM"):
self.send_gripper_home_on_back_press()
self.process_and_send_arm_control()
elif self.xbox_current_control_state == self.XBOX_CONTROL_STATES.index("MINING"):
self.send_mining_commands()
time_diff = time() - start_time
self.msleep(max(int(self.wait_time - time_diff), 0))
self.logger.debug("Stopping Joystick Thread")
def connect_signals_and_slots(self):
self.xbox_control_arm_stylesheet_update_ready__signal.connect(self.xbox_mode_arm_label.setStyleSheet)
self.xbox_control_mining_stylesheet_update_ready__signal.connect(self.xbox_mode_mining_label.setStyleSheet)
self.gripper_mode_normal_stylesheet_update_ready__signal.connect(self.gripper_mode_normal_label.setStyleSheet)
self.gripper_mode_pinch_stylesheet_update_ready__signal.connect(self.gripper_mode_pinch_label.setStyleSheet)
self.gripper_mode_wide_stylesheet_update_ready__signal.connect(self.gripper_mode_wide_label.setStyleSheet)
self.gripper_mode_scissor_stylesheet_update_ready__signal.connect(self.gripper_mode_scissor_label.setStyleSheet)
def change_control_state_if_needed(self):
xbox_state = self.controller.controller_states["xbox_button"]
left_bumper_state = self.controller.controller_states["left_bumper"]
right_bumper_state = self.controller.controller_states["right_bumper"]
if self.last_xbox_button_state == 0 and xbox_state == 1:
self.xbox_current_control_state += 1
self.xbox_current_control_state = self.xbox_current_control_state % len(self.XBOX_CONTROL_STATES)
self.xbox_control_state_just_changed = True
self.last_xbox_button_state = 1
elif self.last_xbox_button_state == 1 and xbox_state == 0:
self.last_xbox_button_state = 0
if self.xbox_control_state_just_changed:
if self.xbox_current_control_state == self.XBOX_CONTROL_STATES.index("ARM"):
self.xbox_control_arm_stylesheet_update_ready__signal.emit(COLOR_GREEN)
self.xbox_control_mining_stylesheet_update_ready__signal.emit(COLOR_NONE)
elif self.xbox_current_control_state == self.XBOX_CONTROL_STATES.index("MINING"):
self.xbox_control_arm_stylesheet_update_ready__signal.emit(COLOR_NONE)
self.xbox_control_mining_stylesheet_update_ready__signal.emit(COLOR_GREEN)
self.xbox_control_state_just_changed = False
if self.xbox_current_control_state == self.XBOX_CONTROL_STATES.index("ARM"):
if self.last_left_bumper_state == 0 and left_bumper_state == 1:
# self.gripper_control_mode = ((self.gripper_control_mode - 1) % len(self.GRIPPER_CONTROL_MODES))
# self.gripper_control_mode_just_changed = True
self.last_left_bumper_state = 1
elif self.last_left_bumper_state == 1 and left_bumper_state == 0:
self.last_left_bumper_state = 0
if self.last_right_bumper_state == 0 and right_bumper_state == 1:
# self.gripper_control_mode = ((self.gripper_control_mode + 1) % len(self.GRIPPER_CONTROL_MODES))
# self.gripper_control_mode_just_changed = True
self.last_right_bumper_state = 1
elif self.last_right_bumper_state == 1 and right_bumper_state == 0:
self.last_right_bumper_state = 0
if self.gripper_control_mode_just_changed:
signal_map = self.GRIPPER_DISPLAY_SIGNAL_MAPPING[self.gripper_control_mode + 1]
for signal in signal_map["SET"]:
signal.emit(COLOR_GREEN)
for signal in signal_map["UNSET"]:
signal.emit(COLOR_NONE)
if "ABS_MOVE" in signal_map:
gripper_control_message = GripperControlMessage()
gripper_control_message.gripper_mode = self.GRIPPER_CONTROL_MODES["SCISSOR"]
gripper_control_message.gripper_position_absolute = signal_map["ABS_MOVE"]
self.gripper_control_publisher.publish(gripper_control_message)
else:
self.send_new_gripper_mode = True
self.gripper_control_mode_just_changed = False
def process_and_send_arm_control(self):
arm_control_message = ArmControlMessage()
gripper_control_message = GripperControlMessage()
should_publish_arm = False
should_publish_gripper = True if self.send_new_gripper_mode else False
if self.send_new_gripper_mode:
gripper_control_message.gripper_position_absolute = 0
else:
gripper_control_message.gripper_position_absolute = -1
gripper_control_message.gripper_mode = self.gripper_control_mode + 1
left_trigger = self.controller.controller_states["left_trigger"]
right_trigger = self.controller.controller_states["right_trigger"]
left_x_axis = self.controller.controller_states["left_x_axis"] if abs(self.controller.controller_states[
"left_x_axis"]) > LEFT_X_AXIS_DEADZONE else 0
left_y_axis = self.controller.controller_states["left_y_axis"] if abs(self.controller.controller_states[
"left_y_axis"]) > LEFT_Y_AXIS_DEADZONE else 0
right_y_axis = self.controller.controller_states["right_y_axis"] if abs(self.controller.controller_states[
"right_y_axis"]) > RIGHT_Y_AXIS_DEADZONE else 0
right_x_axis = self.controller.controller_states["right_x_axis"] if abs(self.controller.controller_states[
"right_x_axis"]) > RIGHT_X_AXIS_DEADZONE else 0
# print left_x_axis, ":", left_y_axis, ":", right_x_axis, ":", right_y_axis
left_trigger_ratio = left_trigger / 255.0
right_trigger_ratio = right_trigger / 255.0
if left_trigger > 0:
should_publish_arm = True
arm_control_message.base = ((left_x_axis / THUMB_STICK_MAX) * BASE_SCALAR) * left_trigger_ratio
arm_control_message.shoulder = ((left_y_axis / THUMB_STICK_MAX) * SHOULDER_SCALAR) * left_trigger_ratio
arm_control_message.elbow = (-(right_y_axis / THUMB_STICK_MAX) * ELBOW_SCALAR) * left_trigger_ratio
arm_control_message.roll = (-(right_x_axis / THUMB_STICK_MAX) * ROLL_SCALAR) * left_trigger_ratio
elif right_trigger > 0:
should_publish_arm = True
should_publish_gripper = True
arm_control_message.wrist_roll = ((left_x_axis / THUMB_STICK_MAX) * BASE_SCALAR) * right_trigger_ratio
# ##### FIXME #####
# Remove this once the arm is fixed
# arm_control_message.wrist_pitch = (-(left_y_axis / THUMB_STICK_MAX) * WRIST_PITCH_SCALAR) * right_trigger_ratio
# #################
gripper_control_message.gripper_position_relative = (-(right_y_axis / THUMB_STICK_MAX) * GRIPPER_MOVEMENT_SCALAR) * right_trigger_ratio
if should_publish_arm:
self.relative_arm_control_publisher.publish(arm_control_message)
if should_publish_gripper:
self.gripper_control_publisher.publish(gripper_control_message)
self.send_new_gripper_mode = False
def send_gripper_home_on_back_press(self):
gripper_control_message = GripperControlMessage()
back_state = self.controller.controller_states["back_button"]
if self.last_back_button_state == 0 and back_state == 1:
gripper_control_message.should_home = True
gripper_control_message.gripper_mode = self.gripper_control_mode + 1
self.gripper_control_publisher.publish(gripper_control_message)
self.last_back_button_state = 1
elif self.last_back_button_state == 1 and back_state == 0:
self.last_back_button_state = 0
def send_mining_commands(self):
left_y_axis = self.controller.controller_states["left_y_axis"] if abs(
self.controller.controller_states["left_y_axis"]) > LEFT_Y_AXIS_DEADZONE else 0
right_y_axis = self.controller.controller_states["right_y_axis"] if abs(self.controller.controller_states[
"right_y_axis"]) > RIGHT_Y_AXIS_DEADZONE else 0
if left_y_axis or right_y_axis:
message = MiningControlMessage()
message.lift_set_absolute = 1024
message.tilt_set_absolute = 1024
message.lift_set_relative = (-(left_y_axis / THUMB_STICK_MAX) * MINING_LIFT_SCALAR)
message.tilt_set_relative = ((right_y_axis / THUMB_STICK_MAX) * MINING_TILT_SCALAR)
message.cal_factor = -1
self.mining_control_publisher.publish(message)
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
start_signal.connect(self.start)
signals_and_slots_signal.connect(self.connect_signals_and_slots)
kill_signal.connect(self.on_kill_threads_requested__slot)
def on_kill_threads_requested__slot(self):
self.run_thread_flag = False

View File

@@ -0,0 +1,175 @@
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore
import logging
from time import time
import spnav
import rospy
from rover_control.msg import MiningControlMessage
#####################################
# Global Variables
#####################################
THREAD_HERTZ = 100
MINING_CONTROL_TOPIC = "/rover_control/mining/control"
Y_ANGULAR_DEADBAND = 0.05
Z_LINEAR_DEADBAND = 0.15
MINING_LIFT_SCALAR = 5
MINING_TILT_SCALAR = 5
#####################################
# Controller Class Definition
#####################################
class SpaceNavControlSender(QtCore.QThread):
spacenav_state_update__signal = QtCore.pyqtSignal(object)
MINING_MODE = 0
ARM_MODE = 1
def __init__(self, shared_objects):
super(SpaceNavControlSender, self).__init__()
# ########## Reference to class init variables ##########
self.shared_objects = shared_objects
self.right_screen = self.shared_objects["screens"]["left_screen"]
# ########## Get the settings instance ##########
self.settings = QtCore.QSettings()
# ########## Get the Pick And Plate instance of the logger ##########
self.logger = logging.getLogger("groundstation")
# ########## Thread Flags ##########
self.run_thread_flag = True
# ########## Class Variables ##########
self.wait_time = 1.0 / THREAD_HERTZ
self.spnav_states = {
"linear_x": 0,
"linear_y": 0,
"linear_z": 0,
"angular_x": 0,
"angular_y": 0,
"angular_z": 0,
"panel_pressed": 0,
"fit_pressed": 0,
"shift_pressed": 0,
"alt_pressed": 0,
"ctrl_pressed": 0,
"esc_pressed": 0,
"1_pressed": 0,
"2_pressed": 0,
"minus_pressed": 0,
"plus_pressed": 0,
"t_pressed": 0,
"l_pressed": 0,
"2d_pressed": 0,
"r_pressed": 0,
"f_pressed": 0
}
self.event_mapping_to_button_mapping = {
11: "panel_pressed",
10: "fit_pressed",
8: "shift_pressed",
7: "alt_pressed",
9: "ctrl_pressed",
6: "esc_pressed",
0: "1_pressed",
1: "2_pressed",
13: "minus_pressed",
12: "plus_pressed",
2: "t_pressed",
3: "l_pressed",
14: "2d_pressed",
4: "r_pressed",
5: "f_pressed"
}
# ##### Mining Control #####
self.mining_control_publisher = rospy.Publisher(MINING_CONTROL_TOPIC, MiningControlMessage, queue_size=1)
self.current_control_mode = self.MINING_MODE
def run(self):
self.logger.debug("Starting SpaceNav Mouse Thread")
spnav.spnav_open()
while self.run_thread_flag:
start_time = time()
self.process_spnav_events()
self.check_control_mode_change()
self.broadcast_control_state()
time_diff = time() - start_time
# self.msleep(max(int((self.wait_time - time_diff) * 1000), 0))
self.logger.debug("Stopping SpaceNav Mouse Thread")
def process_spnav_events(self):
event = spnav.spnav_poll_event()
if event:
# print event
if event.ev_type == spnav.SPNAV_EVENT_MOTION:
self.spnav_states["linear_x"] = event.translation[0] / 350.0
self.spnav_states["linear_y"] = event.translation[2] / 350.0
self.spnav_states["linear_z"] = event.translation[1] / 350.0
self.spnav_states["angular_x"] = event.rotation[2] / 350.0
self.spnav_states["angular_y"] = -(event.rotation[0] / 350.0)
self.spnav_states["angular_z"] = -(event.rotation[1] / 350.0)
# print "x", self.spnav_states["linear_x"], "\t", "y", self.spnav_states["linear_y"], "\t", "z", self.spnav_states["linear_z"]
# print "x", self.spnav_states["angular_x"], "\t", "y", self.spnav_states["angular_y"], "\t", "z", self.spnav_states["angular_z"]
else:
self.spnav_states[self.event_mapping_to_button_mapping[event.bnum]] = event.press
def check_control_mode_change(self):
if self.spnav_states["1_pressed"]:
self.current_control_mode = self.MINING_MODE
elif self.spnav_states["2_pressed"]:
self.current_control_mode = self.ARM_MODE
def broadcast_control_state(self):
if self.current_control_mode == self.MINING_MODE:
self.send_mining_commands()
# self.spacenav_state_update__signal.emit(self.spnav_states)
elif self.current_control_mode == self.ARM_MODE:
pass
# print self.spnav_states["linear_z"], self.spnav_states["angular_y"]
def connect_signals_and_slots(self):
pass
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
start_signal.connect(self.start)
signals_and_slots_signal.connect(self.connect_signals_and_slots)
kill_signal.connect(self.on_kill_threads_requested__slot)
def on_kill_threads_requested__slot(self):
self.run_thread_flag = False

View File

@@ -0,0 +1,127 @@
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore
from os import makedirs, rename, walk, unlink
from os.path import exists, getmtime
from os import environ
import logging
from datetime import datetime
#####################################
# Global Variables
#####################################
MAX_NUM_LOG_FILES = 30
#####################################
# Logger Definition
#####################################
class Logger(QtCore.QObject):
def __init__(self, console_output=True):
super(Logger, self).__init__()
# ########## Local class variables ##########
self.console_output = console_output
# ########## Get the settings instance ##########
self.settings = QtCore.QSettings()
# # ########## Get the Pick And Plate instance of the logger ##########
self.logger = logging.getLogger("groundstation")
# ########## Set variables with useful paths ##########
self.appdata_base_directory = environ["HOME"] + "/.groundstation"
self.log_directory = self.appdata_base_directory + "//logs"
self.log_file_path = self.log_directory + "//log.txt"
# ########## Cleanup old log files ##########
self.__cleanup_log_files()
# ########## Set up logger with desired settings ##########
self.__setup_logger()
# ########## Place divider in log file to see new program launch ##########
self.__add_startup_log_buffer_text()
def __setup_logger(self):
# Get the appdata directory and make the log path if it doesn't exist
if not exists(self.log_directory):
makedirs(self.log_directory)
# Set the debugging level
self.logger.setLevel(logging.DEBUG)
# Make a formatter with the log line format wanted
formatter = logging.Formatter(fmt='%(levelname)s : %(asctime)s : %(message)s', datefmt='%m/%d/%y %H:%M:%S')
# Set up a file handler so everything can be saved and attach it to the logger
file_handler = logging.FileHandler(filename=self.log_file_path)
file_handler.setFormatter(formatter)
file_handler.setLevel(logging.DEBUG)
self.logger.addHandler(file_handler)
# Enable console output if requested
if self.console_output:
console_handler = logging.StreamHandler()
console_handler.setFormatter(formatter)
console_handler.setLevel(logging.DEBUG)
self.logger.addHandler(console_handler)
def __cleanup_log_files(self):
# This copies the existing log.txt file to an old version with a datetime stamp
# It then checks if there are too many log files, and if so, deletes the oldest
if exists(self.log_directory):
# Get the number of log files
num_log_files = self.__get_num_files_in_directory(self.log_directory)
# Check that we actually have log files
if num_log_files > 0:
date_time = datetime.now().strftime("%Y%m%d-%H%M%S")
# If we do, move the current logfile to a backup in the format old_log_datetime
if exists(self.log_file_path):
rename(self.log_file_path, self.log_directory + "\\old_log_" + date_time + ".txt")
# If we have more than the max log files delete the oldest one
if num_log_files >= MAX_NUM_LOG_FILES:
unlink(self.__get_name_of_oldest_file(self.log_directory))
def __add_startup_log_buffer_text(self):
# Prints a header saying when the program started
self.logger.info("########## Application Starting ##########")
@staticmethod
def __get_name_of_oldest_file(input_path):
oldest_file_path = None
previous_oldest_time = 0
# Walk the directory passed in to get all folders and files
for dir_path, dir_names, file_names in walk(input_path):
# Go through all of the filenames found
for file in file_names:
# Recreate the full path and get the modified time of the file
current_path = dir_path + "\\" + file
time = getmtime(current_path)
# Default case for if the variables above have not been initially set
if previous_oldest_time == 0:
previous_oldest_time = time
oldest_file_path = current_path
# Saves the oldest time and file path of the current file if it's older (lower timestamp) than the
# last file saved in the variables
if time < previous_oldest_time:
previous_oldest_time = time
oldest_file_path = current_path
# Returns the path to the oldest file after checking all the files
return oldest_file_path
@staticmethod
def __get_num_files_in_directory(input_path):
# Walk the directory passed in to get all the files
for _, _, file_names in walk(input_path):
# Return the number of files found in the directory
return len(file_names)

View File

@@ -0,0 +1,480 @@
'''
MappingSettings.py: Objected Orientated Google Maps for Python
ReWritten by Chris Pham
Copyright OSURC, orginal code from GooMPy by Alec Singer and Simon D. Levy
This code is free software: you can redistribute it and/or modify
it under the terms of the GNU Lesser General Public License as
published by the Free Software Foundation, either version 3 of the
License, or (at your option) any later version.
This code is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU Lesser General Public License
along with this code. If not, see <http://www.gnu.org/licenses/>.
'''
#####################################
# Imports
#####################################
# Python native imports
import math
import urllib2
from io import StringIO, BytesIO
import os
import time
import PIL.ImageDraw
import PIL.Image
import PIL.ImageFont
import signing
import RoverMapHelper as MapHelper
import cv2
import numpy as np
#####################################
# Constants
#####################################
_KEYS = []
# Number of pixels in half the earth's circumference at zoom = 21
_EARTHPIX = 268435456
# Number of decimal places for rounding coordinates
_DEGREE_PRECISION = 6
_PRECISION_FORMAT = '%.' + str(_DEGREE_PRECISION) + 'f'
# Larget tile we can grab without paying
_TILESIZE = 640
# Fastest rate at which we can download tiles without paying
_GRABRATE = 4
# Pixel Radius of Earth for calculations
_PIXRAD = _EARTHPIX / math.pi
_DISPLAYPIX = _EARTHPIX / 2000
file_pointer = open('key', 'r')
for i in file_pointer:
_KEYS.append(i.rstrip())
file_pointer.close()
class GMapsStitcher(object):
def __init__(self, width, height,
latitude, longitude, zoom,
maptype, radius_meters=None, num_tiles=4, debug=False):
self.helper = MapHelper.MapHelper()
self.latitude = latitude
self.longitude = longitude
self.start_latitude = latitude
self.start_longitude = longitude
self.width = width
self.height = height
self.zoom = zoom
self.maptype = maptype
self.radius_meters = radius_meters
self.num_tiles = num_tiles
self.display_image = self.helper.new_image(width, height)
self.debug = debug
# Get the big image here
self._fetch()
self.center_display(latitude, longitude)
def __str__(self):
"""
This string returns when used in a print statement
Useful for debugging and to print current state
returns STRING
"""
string_builder = ""
string_builder += ("Center of the displayed map: %4f, %4f\n" %
(self.center_x, self.center_y))
string_builder += ("Center of the big map: %4fx%4f\n" %
(self.start_longitude, self.start_longitude))
string_builder += ("Current latitude is: %4f, %4f\n" %
(self.longitude, self.latitude))
string_builder += ("The top-left of the box: %dx%d\n" %
(self.left_x, self.upper_y))
string_builder += ("Number of tiles genreated: %dx%d\n" %
(self.num_tiles, self.num_tiles))
string_builder += "Map Type: %s\n" % (self.maptype)
string_builder += "Zoom Level: %s\n" % (self.zoom)
string_builder += ("Dimensions of Big Image: %dx%d\n" %
(self.big_image.size[0], self.big_image.size[1]))
string_builder += ("Dimensions of Displayed Image: %dx%d\n" %
(self.width, self.height))
string_builder += ("LatLong of Northwest Corner: %4f, %4f\n" %
(self.northwest))
string_builder += ("LatLong of Southeast Corner: %4f, %4f\n" %
(self.southeast))
return string_builder
def _grab_tile(self, longitude, latitude, sleeptime=0):
"""
This will return the tile at location longitude x latitude.
Includes a sleep time to allow for free use if there is no API key
returns PIL.IMAGE OBJECT
"""
# Make the url string for polling
# GET request header gets appended to the string
urlbase = 'https://maps.googleapis.com/maps/api/staticmap?'
urlbase += 'center=' + _PRECISION_FORMAT + ',' + _PRECISION_FORMAT + '&zoom=%d&maptype=%s'
urlbase += '&size=%dx%d&format=png&key=%s'
# Fill the formatting
specs = (self.helper.fast_round(latitude, _DEGREE_PRECISION),
self.helper.fast_round(longitude, _DEGREE_PRECISION),
self.zoom, self.maptype, _TILESIZE, _TILESIZE, _KEYS[0])
filename = 'Resources/Maps/' + ((_PRECISION_FORMAT + '_' + _PRECISION_FORMAT + '_%d_%s_%d_%d_%s') % specs)
filename += '.png'
# Tile Image object
tile_object = None
if os.path.isfile(filename):
tile_object = PIL.Image.open(filename)
# If file on filesystem
else:
# make the url
url = urlbase % specs
url = signing.sign_url(url, _KEYS[1])
try:
result = urllib2.urlopen(urllib2.Request(url)).read()
except urllib2.HTTPError, e:
print "Error accessing url for reason:", e
print url
return
tile_object = PIL.Image.open(BytesIO(result))
if not os.path.exists('Resources/Maps'):
os.mkdir('Resources/Maps')
tile_object.save(filename)
# Added to prevent timeouts on Google Servers
time.sleep(sleeptime)
return tile_object
def _pixels_to_lon(self, iterator, lon_pixels):
"""
This converts pixels to degrees to be used in
fetching squares and generate correct squares
returns FLOAT(degrees)
"""
# Magic Lines, no idea
degrees = self.helper.pixels_to_degrees(
(iterator - self.num_tiles / 2) * _TILESIZE, self.zoom)
return math.degrees((lon_pixels + degrees - _EARTHPIX) / _PIXRAD)
def _pixels_to_lat(self, iterator, lat_pixels):
"""
This converts pixels to latitude using meridian projection
to get the latitude to generate squares
returns FLOAT(degrees)
"""
# Magic Lines
return math.degrees(math.pi / 2 - 2 * math.atan(math.exp(((lat_pixels +
self.helper.pixels_to_degrees(
(iterator - self.num_tiles /
2) * _TILESIZE, self.zoom)) -
_EARTHPIX) / _PIXRAD)))
def fetch_tiles(self):
"""
Function that handles fetching of files from init'd variables
returns PIL.IMAGE OBJECT, (WEST, NORTH), (EAST, SOUTH)
North/East/South/West are in FLOAT(degrees)
"""
# cap floats to precision amount
self.latitude = self.helper.fast_round(self.latitude,
_DEGREE_PRECISION)
self.longitude = self.helper.fast_round(self.longitude,
_DEGREE_PRECISION)
# number of tiles required to go from center
# latitude to desired radius in meters
if self.radius_meters is not None:
self.num_tiles = (int(
round(2 * self.helper.pixels_to_meters(
self.latitude, self.zoom) /
(_TILESIZE / 2. / self.radius_meters))))
lon_pixels = _EARTHPIX + self.longitude * math.radians(_PIXRAD)
sin_lat = math.sin(math.radians(self.latitude))
lat_pixels = _EARTHPIX - _PIXRAD * math.log((1 + sin_lat) / (1 - sin_lat)) / 2
self.big_size = self.num_tiles * _TILESIZE
big_image = self.helper.new_image(self.big_size, self.big_size)
for j in range(self.num_tiles):
lon = self._pixels_to_lon(j, lon_pixels)
for k in range(self.num_tiles):
lat = self._pixels_to_lat(k, lat_pixels)
tile = self._grab_tile(lon, lat)
big_image.paste(tile, (j * _TILESIZE, k * _TILESIZE))
west = self._pixels_to_lon(0, lon_pixels)
east = self._pixels_to_lon(self.num_tiles - 1, lon_pixels)
north = self._pixels_to_lat(0, lat_pixels)
south = self._pixels_to_lat(self.num_tiles - 1, lat_pixels)
return big_image, (north, west), (south, east)
def move_pix(self, dx, dy):
"""
Function gets change in x and y (dx, dy)
then displaces the displayed map that amount
NO RETURN
"""
self._constrain_x(dx)
self._constrain_y(dy)
self.update()
def _constrain_x(self, diff):
"""
Helper for move_pix
"""
new_value = self.left_x - diff
if ((not new_value > 0) and
(new_value < self.big_image.size[0] - self.width)):
return self.left_x
else:
return new_value
def _constrain_y(self, diff):
"""
Helper for move_pix
"""
new_value = self.upper_y - diff
if ((not new_value > 0) and
(new_value < self.big_image.size[1] - self.height)):
return self.upper_y
else:
return new_value
def update(self):
"""
Function remakes display image using top left corners
"""
self.display_image.paste(self.big_image, (-self.left_x, -self.upper_y))
# self.display_image.resize((self.image_zoom, self.image_zoom))
def _fetch(self):
"""
Function generates big image
"""
self.big_image, self.northwest, self.southeast = self.fetch_tiles()
def move_latlon(self, lat, lon):
"""
Function to move the object/rover
"""
x, y = self._get_cartesian(lat, lon)
self._constrain_x(self.center_x - x)
self._constrain_y(self.center_y - y)
self.update()
def _get_cartesian(self, lat, lon):
"""
Helper for getting the x, y given lat and lon
returns INT, INT (x, y)
"""
viewport_lat_nw, viewport_lon_nw = self.northwest
viewport_lat_se, viewport_lon_se = self.southeast
# print "Lat:", viewport_lat_nw, viewport_lat_se
# print "Lon:", viewport_lon_nw, viewport_lon_se
viewport_lat_diff = viewport_lat_nw - viewport_lat_se
viewport_lon_diff = viewport_lon_se - viewport_lon_nw
# print viewport_lon_diff, viewport_lat_diff
bigimage_width = self.big_image.size[0]
bigimage_height = self.big_image.size[1]
pixel_per_lat = bigimage_height / viewport_lat_diff
pixel_per_lon = bigimage_width / viewport_lon_diff
# print "Pixel per:", pixel_per_lat, pixel_per_lon
new_lat_gps_range_percentage = (viewport_lat_nw - lat)
new_lon_gps_range_percentage = (lon - viewport_lon_nw)
# print lon, viewport_lon_se
x = new_lon_gps_range_percentage * pixel_per_lon
y = new_lat_gps_range_percentage * pixel_per_lat
return int(x), int(y)
def add_gps_location(self, lat, lon, shape, size, fill):
"""
Function adds a shape at lat x lon
"""
x, y = self._get_cartesian(lat, lon)
draw = PIL.ImageDraw.Draw(self.big_image)
if shape is "ellipsis":
draw.ellipsis((x - size, y - size, x + size, y + size), fill)
else:
draw.rectangle([x - size, y - size, x + size, y + size], fill)
self.update()
def center_display(self, lat, lon):
"""
Function centers the display image
"""
x, y = self._get_cartesian(lat, lon)
self.center_x = x
self.center_y = y
self.left_x = (self.center_x - (self.width / 2))
self.upper_y = (self.center_y - (self.height / 2))
self.update()
# def update_rover_map_location(self, lat, lon):
# print "I did nothing"
# def draw_circle(self, lat, lon, radius, fill):
# print "I did nothing"
def connect_signals_and_slots(self):
pass
class OverlayImage(object):
def __init__(self, latitude, longitude, northwest, southeast,
big_width, big_height, width, height):
self.northwest = northwest
self.southeast = southeast
self.latitude = latitude
self.longitude = longitude
self.big_width = big_width
self.big_height = big_height
self.width = width
self.height = height
self.big_image = None
self.big_image_copy = None
self.display_image = None
self.display_image_copy = None
self.indicator = None
self.helper = MapHelper.MapHelper()
x, y = self._get_cartesian(latitude, longitude)
self.center_x = x
self.center_y = y
self.left_x = (self.center_x - (self.width / 2))
self.upper_y = (self.center_y - (self.height / 2))
self.generate_image_files()
self.write_once = True
# Text Drawing Variables
self.font = cv2.FONT_HERSHEY_TRIPLEX
self.font_thickness = 1
self.font_baseline = 0
self.nav_coordinates_text_image = None
def generate_image_files(self):
"""
Creates big_image and display image sizes
Returns NONE
"""
self.big_image = self.helper.new_image(self.big_width, self.big_height,
True)
self.big_image_copy = self.big_image.copy()
self.display_image = self.helper.new_image(self.width, self.height,
True)
self.display_image_copy = self.display_image.copy()
self.load_rover_icon()
self.indicator.save("location.png")
def _get_cartesian(self, lat, lon):
"""
Helper for getting the x, y given lat and lon
returns INT, INT (x, y)
"""
viewport_lat_nw, viewport_lon_nw = self.northwest
viewport_lat_se, viewport_lon_se = self.southeast
# print "Lat:", viewport_lat_nw, viewport_lat_se
# print "Lon:", viewport_lon_nw, viewport_lon_se
viewport_lat_diff = viewport_lat_nw - viewport_lat_se
viewport_lon_diff = viewport_lon_se - viewport_lon_nw
# print viewport_lon_diff, viewport_lat_diff
pixel_per_lat = self.big_height / viewport_lat_diff
pixel_per_lon = self.big_width / viewport_lon_diff
# print "Pixel per:", pixel_per_lat, pixel_per_lon
new_lat_gps_range_percentage = (viewport_lat_nw - lat)
new_lon_gps_range_percentage = (lon - viewport_lon_nw)
# print lon, viewport_lon_se
x = new_lon_gps_range_percentage * pixel_per_lon
y = new_lat_gps_range_percentage * pixel_per_lat
return int(x), int(y)
def update_new_location(self, latitude, longitude,
compass, navigation_list, landmark_list):
self.big_image = self.big_image_copy.copy()
self.display_image = self.display_image_copy.copy()
size = 5
draw = PIL.ImageDraw.Draw(self.big_image)
for element in navigation_list:
x, y = self._get_cartesian(float(element[1]), float(element[2]))
draw.text((x + 10, y - 5), str(element[0]))
draw.ellipse((x - size, y - size, x + size, y + size), fill=(element[3].red(), element[3].green(), element[3].blue()))
for element in landmark_list:
x, y = self._get_cartesian(element[1], element[2])
draw.text((x + 10, y - 5), str(element[0]))
draw.ellipse((x - size, y - size, x + size, y + size), fill=(element[3].red(), element[3].green(), element[3].blue()))
self._draw_rover(latitude, longitude, compass)
self.update(latitude, longitude)
return self.display_image
def load_rover_icon(self):
self.indicator = PIL.Image.open("Resources/Images/rover.png").resize((40, 40))
def _draw_rover(self, lat, lon, angle=0):
x, y = self._get_cartesian(lat, lon)
x -= 25 # Half the height of the icon
y -= 25
rotated = self.indicator.copy()
rotated = rotated.rotate(-angle, resample=PIL.Image.BICUBIC)
# rotated.save("rotated.png")
self.big_image.paste(rotated, (x, y), rotated)
if self.write_once:
# self.display_image.save("Something.png")
self.write_once = False
def update(self, latitude, longitude):
# self.left_x -= 50
# self.upper_y -= 50
self.display_image.paste(self.big_image, (-self.left_x, -self.upper_y))
# self._draw_coordinate_text(latitude, longitude)
def connect_signals_and_slots(self):
pass

View File

@@ -0,0 +1,375 @@
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore, QtWidgets, QtGui
from PIL.ImageQt import ImageQt
from PIL import Image
import PIL.ImageDraw
import PIL.Image
import PIL.ImageFont
import numpy
import logging
import rospy
from tf import transformations
from scipy.interpolate import interp1d
import math
from sensor_msgs.msg import Imu
# Custom Imports
import RoverMap
from Resources.Settings import MappingSettings
from sensor_msgs.msg import NavSatFix
#####################################
# Global Variables
#####################################
# put some stuff here later so you can remember
GPS_POSITION_TOPIC = "/rover_odometry/fix"
IMU_DATA_TOPIC = "/rover_odometry/imu/data"
MAP_WIDGET_WIDTH = float(1280)
MAP_WIDGET_HEIGHT = float(720)
MAP_WIDGET_RATIO = MAP_WIDGET_WIDTH / MAP_WIDGET_HEIGHT
class RoverMapCoordinator(QtCore.QThread):
pixmap_ready_signal = QtCore.pyqtSignal()
change_waypoint_signal = QtCore.pyqtSignal()
zoom_level_enabled_state_update__signal = QtCore.pyqtSignal(int)
def __init__(self, shared_objects):
super(RoverMapCoordinator, self).__init__()
self.shared_objects = shared_objects
self.left_screen = self.shared_objects["screens"]["left_screen"]
self.mapping_label = self.left_screen.mapping_label # type:QtWidgets.QLabel
self.navigation_label = self.left_screen.navigation_waypoints_table_widget
self.landmark_label = self.left_screen.landmark_waypoints_table_widget
self.map_selection_combo_box = self.left_screen.map_selection_combo_box # type: QtWidgets.QComboBox
self.map_zoom_level_combo_box = self.left_screen.map_zoom_level_combo_box # type: QtWidgets.QComboBox
self.setings = QtCore.QSettings()
self.logger = logging.getLogger("groundstation")
self.gps_position_subscriber = rospy.Subscriber(GPS_POSITION_TOPIC, NavSatFix,
self.gps_position_updated_callback)
self.run_thread_flag = True
self.setup_map_flag = True
self.google_maps_object = None
self.map_image = None
self.map_image_copy = None
self.overlay_image = None
self.overlay_image_object = None
self.loading_image_pixmap = QtGui.QPixmap.fromImage(
ImageQt(Image.open("Resources/Images/maps_loading.png").resize((1280, 720), Image.BICUBIC)))
self.map_pixmap = self.loading_image_pixmap
self.last_map_pixmap_cache_key = None
self.longitude = 0
self.latitude = 0
self.last_heading = 0
self.imu_data = None
self.new_imu_data = False
self.yaw = None
self.pitch = None
self.roll = None
self.euler_interpolator = interp1d([math.pi, -math.pi], [-180, 180])
self.imu_data_subscriber = rospy.Subscriber(IMU_DATA_TOPIC, Imu, self.on_imu_data_received)
self.zoom_pan_x_location = 0
self.zoom_pan_y_location = 0
self.zoom_subtraction = 0
self.x_drag = 0
self.y_drag = 0
self.x_drag_start = -1
self.y_drag_start = -1
self.x_drag_end = -1
self.y_drag_end = -1
self.map_selection_name = ""
self.map_selection_latitude = 0
self.map_selection_longitude = 0
self.map_selection_zoom = 0
self.setup_mapping_locations()
def run(self):
self.logger.debug("Starting Map Coordinator Thread")
self.pixmap_ready_signal.emit() # This gets us the loading map
# self.precache_all_maps()
while self.run_thread_flag:
if self.setup_map_flag:
self._map_setup()
self.setup_map_flag = False
else:
if self.new_imu_data:
self.calculate_euler_from_imu()
self.new_imu_data = False
self._get_map_image()
self.msleep(10)
self.logger.debug("Stopping Map Coordinator Thread")
def setup_mapping_locations(self):
locations = [location for location in MappingSettings.MAPPING_LOCATIONS]
self.map_selection_combo_box.addItems(locations)
self.update_settings_from_selection()
self.map_selection_combo_box.setCurrentText(self.map_selection_name)
self.update_zoom_combo_box_items(
MappingSettings.MAPPING_LOCATIONS[MappingSettings.LAST_SELECTION]["valid_zoom_options"],
MappingSettings.LAST_ZOOM_LEVEL)
def update_settings_from_selection(self):
self.map_selection_latitude = MappingSettings.MAPPING_LOCATIONS[MappingSettings.LAST_SELECTION]["latitude"]
self.map_selection_longitude = MappingSettings.MAPPING_LOCATIONS[MappingSettings.LAST_SELECTION]["longitude"]
self.map_selection_zoom = MappingSettings.LAST_ZOOM_LEVEL
self.map_selection_name = MappingSettings.LAST_SELECTION
def precache_all_maps(self):
print "Caching all map options!!!"
for map in MappingSettings.MAPPING_LOCATIONS:
lat = MappingSettings.MAPPING_LOCATIONS[map]["latitude"]
lon = MappingSettings.MAPPING_LOCATIONS[map]["longitude"]
for zoom in MappingSettings.MAPPING_LOCATIONS[map]["valid_zoom_options"]:
print "Caching map: %s at zoom %d" % (map, zoom)
try:
RoverMap.GMapsStitcher(1280,
720,
lat,
lon,
zoom,
'satellite',
None, 20)
except:
print "Could not cache map: %s at zoom %d" % (map, zoom)
print "Finished caching map: %s at zoom %d" % (map, zoom)
print "Map cache complete!"
def _map_setup(self):
self.update_zoom_combo_box_items(
MappingSettings.MAPPING_LOCATIONS[MappingSettings.LAST_SELECTION]["valid_zoom_options"],
MappingSettings.LAST_ZOOM_LEVEL)
self.map_image = None
self.map_pixmap = self.loading_image_pixmap
self.pixmap_ready__slot()
self.google_maps_object = None
self.google_maps_object = RoverMap.GMapsStitcher(1280,
720,
self.map_selection_latitude,
self.map_selection_longitude,
self.map_selection_zoom,
'satellite',
None, 20)
self.overlay_image_object = None
self.overlay_image_object = (
RoverMap.OverlayImage(self.map_selection_latitude, self.map_selection_longitude,
self.google_maps_object.northwest,
self.google_maps_object.southeast,
self.google_maps_object.big_image.size[0],
self.google_maps_object.big_image.size[1],
1280, 720))
def _get_map_image(self):
while self.map_image is None:
self.map_image = self.google_maps_object.display_image
if self.map_image:
self.map_image_copy = self.map_image.copy()
self.update_overlay()
self.map_image = self.map_image_copy.copy()
self.map_image.paste(self.overlay_image_object.display_image,
(0, 0),
self.overlay_image_object.display_image)
# ##### Zoom testing! #####
if self.zoom_subtraction:
self.zoom_subtraction = self.constrain(self.zoom_subtraction, 0, 520)
crop_x_start = ((self.zoom_subtraction * MAP_WIDGET_RATIO) / 2) - self.x_drag - self.x_drag_end
crop_y_start = (self.zoom_subtraction / 2) - self.y_drag - self.y_drag_end
crop_x_end = (MAP_WIDGET_WIDTH - (
(self.zoom_subtraction * MAP_WIDGET_RATIO) / 2)) - self.x_drag - self.x_drag_end
crop_y_end = (MAP_WIDGET_HEIGHT - (self.zoom_subtraction / 2)) - self.y_drag - self.y_drag_end
crop_box = (int(crop_x_start), int(crop_y_start), int(crop_x_end), int(crop_y_end))
self.map_image = self.map_image.crop(crop_box)
self.map_image = self.map_image.resize((1280, 720), resample=PIL.Image.BICUBIC)
# ##### Draw coordinates #####
self._draw_coordinate_text(self.latitude, self.longitude)
qim = ImageQt(self.map_image)
self.map_pixmap = QtGui.QPixmap.fromImage(qim)
# if self.map_pixmap.cacheKey() != self.last_map_pixmap_cache_key:
# self.last_map_pixmap_cache_key = self.map_pixmap.cacheKey()
self.pixmap_ready_signal.emit()
def _draw_coordinate_text(self, latitude, longitude):
if latitude == 0 and longitude == 0:
location_text = "LAT: NO FIX\nLON: NO FIX"
else:
location_text = "LAT: %+014.9f\nLON: %+014.9f" % (latitude, longitude)
font = PIL.ImageFont.truetype("UbuntuMono-R", size=20)
new_image = PIL.Image.new('RGBA', (200, 45), "black")
draw = PIL.ImageDraw.Draw(new_image)
draw.multiline_text((5, 0), location_text, font=font)
self.map_image.paste(new_image, (0, 0))
def connect_signals_and_slots(self):
self.pixmap_ready_signal.connect(self.pixmap_ready__slot)
self.change_waypoint_signal.connect(self.update_overlay)
self.mapping_label.mouseReleaseEvent = self.__mouse_released_event
self.mapping_label.wheelEvent = self.__mouse_wheel_event
self.mapping_label.mouseMoveEvent = self.__mouse_move_event
self.map_selection_combo_box.currentTextChanged.connect(self.map_selection_changed__slot)
self.map_zoom_level_combo_box.currentTextChanged.connect(self.zoom_selection_changed__slot)
def on_kill_threads_requested_slot(self):
self.run_thread_flag = False
def setup_signals(self, start_signal, signals_and_slots_signal,
kill_signal):
start_signal.connect(self.start)
signals_and_slots_signal.connect(self.connect_signals_and_slots)
kill_signal.connect(self.on_kill_threads_requested_slot)
def pixmap_ready__slot(self):
self.mapping_label.setPixmap(self.map_pixmap)
def _get_table_elements(self, UI_element):
temp_list = []
count = UI_element.rowCount()
for row in range(0, count):
name = UI_element.item(row, 0).text()
lat = float(UI_element.item(row, 1).text())
lng = float(UI_element.item(row, 2).text())
color = UI_element.item(row, 3).background().color()
temp_tuple = (name, lat, lng, color)
temp_list.append(temp_tuple)
return temp_list
def update_overlay(self):
if not numpy.isnan(self.latitude) and not numpy.isnan(self.longitude):
latitude = float(self.latitude)
longitude = float(self.longitude)
navigation_list = self._get_table_elements(self.navigation_label)
landmark_list = self._get_table_elements(self.landmark_label)
self.overlay_image = self.overlay_image_object.update_new_location(
latitude,
longitude,
self.last_heading,
navigation_list,
landmark_list)
def gps_position_updated_callback(self, data):
self.latitude = data.latitude
self.longitude = data.longitude
def on_imu_data_received(self, data):
self.imu_data = data
self.new_imu_data = True
def calculate_euler_from_imu(self):
quat = (
self.imu_data.orientation.x,
self.imu_data.orientation.y,
self.imu_data.orientation.z,
self.imu_data.orientation.w,
)
self.roll, self.pitch, self.yaw = transformations.euler_from_quaternion(quat)
self.last_heading = (self.euler_interpolator(self.yaw) + MappingSettings.DECLINATION_OFFSET) % 360
def __mouse_released_event(self, _):
self.x_drag_start = -1
self.y_drag_start = -1
self.x_drag_end += self.x_drag
self.y_drag_end += self.y_drag
self.x_drag = 0
self.x_drag = 0
def __mouse_wheel_event(self, event):
self.zoom_subtraction += event.angleDelta().y() / 12
def __mouse_move_event(self, event):
if self.x_drag_start != -1 and self.x_drag_start != -1:
buttons = event.buttons()
if buttons == QtCore.Qt.LeftButton:
x_pos = event.pos().x()
y_pos = event.pos().y()
dx = x_pos - self.x_drag_start
dy = y_pos - self.y_drag_start
self.x_drag = dx
self.y_drag = dy
else:
self.x_drag_start = event.pos().x()
self.y_drag_start = event.pos().y()
def update_zoom_combo_box_items(self, zooms, selection):
self.map_zoom_level_combo_box.clear()
self.map_zoom_level_combo_box.addItems([str(item) for item in zooms])
self.map_zoom_level_combo_box.setCurrentText(str(selection))
def zoom_selection_changed__slot(self, zoom):
if zoom:
MappingSettings.LAST_ZOOM_LEVEL = int(zoom)
self.map_selection_zoom = int(zoom)
self.setup_map_flag = True
def map_selection_changed__slot(self, selection):
MappingSettings.LAST_SELECTION = selection
MappingSettings.LAST_ZOOM_LEVEL = MappingSettings.MAPPING_LOCATIONS[selection]["default_zoom"]
self.update_settings_from_selection()
self.setup_map_flag = True
self.map_selection_name = selection
@staticmethod
def constrain(val, min_val, max_val):
return min(max_val, max(min_val, val))

View File

@@ -0,0 +1,46 @@
import PIL.Image
import math
class MapHelper(object):
@staticmethod
def new_image(width, height, alpha=False):
"""
Generates a new image using PIL.Image module
returns PIL.IMAGE OBJECT
"""
if alpha is True:
return PIL.Image.new('RGBA', (width, height), (0, 0, 0, 0))
else:
return PIL.Image.new('RGBA', (width, height))
@staticmethod
def fast_round(value, precision):
"""
Function to round values instead of using python's
return INT
"""
return int(value * 10 ** precision) / 10. ** precision
@staticmethod
def pixels_to_degrees(pixels, zoom):
"""
Generates pixels to be expected at zoom levels
returns INT
"""
return pixels * 2 ** (21-zoom)
@staticmethod
def pixels_to_meters(latitude, zoom):
"""
Function generates how many pixels per meter it
should be from the projecction
returns FLOAT
"""
# https://groups.google.com/forum/#!topic/google-maps-js-api-v3/hDRO4oHVSeM
return 2 ** zoom / (156543.03392 * math.cos(math.radians(latitude)))

View File

@@ -0,0 +1,53 @@
#!/usr/bin/python
# -*- coding: utf-8 -*-
""" Signs a URL using a URL signing secret """
import hashlib
import hmac
import base64
import urlparse
def sign_url(input_url=None, secret=None):
""" Sign a request URL with a URL signing secret.
Usage:
from urlsigner import sign_url
signed_url = sign_url(input_url=my_url, secret=SECRET)
Args:
input_url - The URL to sign
secret - Your URL signing secret
Returns:
The signed request URL
"""
if not input_url or not secret:
raise Exception("Both input_url and secret are required")
url = urlparse.urlparse(input_url)
# We only need to sign the path+query part of the string
url_to_sign = url.path + "?" + url.query
# Decode the private key into its binary format
# We need to decode the URL-encoded private key
decoded_key = base64.urlsafe_b64decode(secret)
# Create a signature using the private key and the URL-encoded
# string using HMAC SHA1. This signature will be binary.
signature = hmac.new(decoded_key, url_to_sign, hashlib.sha1)
# Encode the binary signature into base64 for use within a URL
encoded_signature = base64.urlsafe_b64encode(signature.digest())
original_url = url.scheme + "://" + url.netloc + url.path + "?" + url.query
# Return signed URL
return original_url + "&signature=" + encoded_signature
if __name__ == "__main__":
input_url = raw_input("URL to Sign: ")
secret = raw_input("URL signing secret: ")
print "Signed URL: " + sign_url(input_url, secret)

View File

@@ -0,0 +1,201 @@
# coding=utf-8
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore, QtWidgets, QtGui
import logging
from time import time
import paramiko
#####################################
# Global Variables
#####################################
THREAD_HERTZ = 5
IP = "192.168.1.10"
USER = "nvidia"
PASS = "nvidia"
#####################################
# BashConsole Class Definition
#####################################
class BashConsole(QtCore.QThread):
text_update_ready__signal = QtCore.pyqtSignal(str)
def __init__(self, shared_objects):
super(BashConsole, self).__init__()
# ########## Reference to class init variables ##########
self.shared_objects = shared_objects
self.left_screen = self.shared_objects["screens"]["left_screen"]
self.console_text_edit = self.left_screen.console_line_edit # type: QtWidgets.QTextEdit
self.ssh_console_command_line_edit = self.left_screen.ssh_console_command_line_edit # type:QtWidgets.QLineEdit
self.ssh_scan_for_hosts_button = self.left_screen.ssh_scan_for_hosts_button # type: QtWidgets.QPushButton
self.ssh_host_line_edit = self.left_screen.ssh_host_line_edit # type: QtWidgets.QLineEdit
self.ssh_list_wifi_button = self.left_screen.ssh_list_wifi_button # type: QtWidgets.QPushButton
self.ssh_equipment_login_button = self.left_screen.ssh_equipment_login_button # type: QtWidgets.QPushButton
self.ssh_equipment_logout_button = self.left_screen.ssh_equipment_logout_button # type: QtWidgets.QPushButton
self.ssh_equipment_status_button = self.left_screen.ssh_equipment_status_button # type: QtWidgets.QPushButton
self.ssh_equipment_start_button = self.left_screen.ssh_equipment_start_button # type: QtWidgets.QPushButton
self.ssh_equipment_stop_button = self.left_screen.ssh_equipment_stop_button # type: QtWidgets.QPushButton
self.ssh_ssid_line_edit = self.left_screen.ssh_ssid_line_edit # type:QtWidgets.QLineEdit
self.ssh_connect_ssid_push_button = self.left_screen.ssh_ssid_push_button # type: QtWidgets.QPushButton
self.ssh_disconnect_wifi_button = self.left_screen.ssh_disconnect_wifi_button # type: QtWidgets.QPushButton
# ########## Get the settings instance ##########
self.settings = QtCore.QSettings()
# ########## Get the Pick And Plate instance of the logger ##########
self.logger = logging.getLogger("groundstation")
# ########## Thread Flags ##########
self.run_thread_flag = True
# ########## Class Variables ##########
self.bash_process = None
self.new_widget = None
self.window = None
self.wait_time = 1.0 / THREAD_HERTZ
self.ssh_client = None
self.set_text_contents = ""
self.new_command_text = ""
self.new_command = False
def run(self):
while not self.ssh_client:
try:
self.ssh_client = paramiko.SSHClient()
self.ssh_client.set_missing_host_key_policy(paramiko.AutoAddPolicy())
self.ssh_client.connect(IP, username=USER, password=PASS, compress=True)
except:
print "No connection"
if not self.run_thread_flag:
return
self.ssh_client = None
self.msleep(1000)
while self.run_thread_flag:
start_time = time()
if self.new_command:
_, ssh_stdout, ssh_stderr = self.ssh_client.exec_command(self.new_command_text)
stdout_read = ssh_stdout.read()
stderr_read = ssh_stderr.read()
output = ""
output += "\n%s@%s:$" % (USER, IP)
output += self.new_command_text + "\n"
output += stdout_read.decode("utf-8") if stdout_read else ""
output += stderr_read.decode("utf-8") if stderr_read else ""
self.set_text_contents += output
self.text_update_ready__signal.emit(self.set_text_contents)
self.new_command = False
time_diff = time() - start_time
self.msleep(max(int(self.wait_time - time_diff), 0))
del self.bash_process
def on_text_readout_updated__slot(self):
self.console_text_edit.moveCursor(QtGui.QTextCursor.End)
def on_text_editing_finished__slot(self):
self.new_command_text = self.ssh_console_command_line_edit.text()
self.new_command = True
def on_list_wifi_button_pressed__slot(self):
self.new_command_text = "nmcli dev wifi list"
self.new_command = True
def on_login_button_pressed__slot(self):
current_ip = self.ssh_host_line_edit.text()
self.new_command_text = "python equipment_servicing_interface.py '%s' 'LOGIN MTECH GITRDONE' HELP" % current_ip
print self.new_command_text
self.new_command = True
def on_logout_button_pressed__slot(self):
current_ip = self.ssh_host_line_edit.text()
self.new_command_text = "python equipment_servicing_interface.py '%s' LOGOUT" % current_ip
self.new_command = True
def on_status_button_pressed__slot(self):
current_ip = self.ssh_host_line_edit.text()
self.new_command_text = "python equipment_servicing_interface.py '%s' STATUS" % current_ip
self.new_command = True
def on_start_button_pressed__slot(self):
current_ip = self.ssh_host_line_edit.text()
self.new_command_text = "python equipment_servicing_interface.py '%s' START" % current_ip
self.new_command = True
def on_stop_button_pressed__slot(self):
current_ip = self.ssh_host_line_edit.text()
self.new_command_text = "python equipment_servicing_interface.py '%s' STOP" % current_ip
self.new_command = True
def on_ssh_scan_for_hosts_pressed__slot(self):
current_ip = self.ssh_host_line_edit.text()
find_dot = current_ip.rfind(".")
if find_dot > 0:
current_ip = current_ip[:find_dot + 1] + "0"
self.new_command_text = "nmap -sP %s/24 -oG - | awk '/Up$/{print $2}'" % current_ip
self.new_command = True
else:
self.set_text_contents += "IP address for range search not valid. Try again."
self.text_update_ready__signal.emit(self.set_text_contents)
def on_connect_ssid_button_pressed__slot(self):
ssid_text = self.ssh_ssid_line_edit.text()
self.new_command_text = "sudo nmcli dev wifi connect %s" % ssid_text
self.new_command = True
def on_disconnect_ssid_button_pressed__slot(self):
ssid_text = self.ssh_ssid_line_edit.text()
self.new_command_text = "sudo nmcli con down id %s ; sudo nmcli connection delete %s" % (ssid_text, ssid_text)
self.new_command = True
def connect_signals_and_slots(self):
self.text_update_ready__signal.connect(self.console_text_edit.setText)
self.ssh_console_command_line_edit.editingFinished.connect(self.on_text_editing_finished__slot)
self.console_text_edit.textChanged.connect(self.on_text_readout_updated__slot)
self.ssh_scan_for_hosts_button.clicked.connect(self.on_ssh_scan_for_hosts_pressed__slot)
self.ssh_equipment_login_button.clicked.connect(self.on_login_button_pressed__slot)
self.ssh_equipment_logout_button.clicked.connect(self.on_logout_button_pressed__slot)
self.ssh_equipment_status_button.clicked.connect(self.on_status_button_pressed__slot)
self.ssh_equipment_start_button.clicked.connect(self.on_start_button_pressed__slot)
self.ssh_equipment_stop_button.clicked.connect(self.on_stop_button_pressed__slot)
self.ssh_list_wifi_button.clicked.connect(self.on_list_wifi_button_pressed__slot)
self.ssh_connect_ssid_push_button.clicked.connect(self.on_connect_ssid_button_pressed__slot)
self.ssh_disconnect_wifi_button.clicked.connect(self.on_disconnect_ssid_button_pressed__slot)
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
start_signal.connect(self.start)
signals_and_slots_signal.connect(self.connect_signals_and_slots)
kill_signal.connect(self.on_kill_threads_requested__slot)
def on_kill_threads_requested__slot(self):
self.run_thread_flag = False

View File

@@ -0,0 +1,257 @@
# coding=utf-8
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore, QtWidgets
import logging
import rospy
from rover_control.msg import MiningStatusMessage, MiningControlMessage, CameraControlMessage
from rover_science.msg import SoilSensorStatusMessage
from std_msgs.msg import Float64
#####################################
# Global Variables
#####################################
MINING_STATUS_TOPIC = "/rover_control/mining/status"
MINING_CONTROL_TOPIC = "/rover_control/mining/control"
SCALE_MEASUREMENT_TOPIC = "/rover_control/scale/measurement"
SOIL_PROBE_TOPIC = "/rover_science/soil_probe/data"
CAMERA_CONTROL_TOPIC = "/rover_control/camera/control"
TRAVEL_POSITION_LIFT = 110
TRAVEL_POSITION_TILT = 1023
MEASURE_POSITION_LIFT = 350
MEASURE_POSITION_TILT = 1023
SCOOP_POSITION_LIFT = 228
SCOOP_POSITION_TILT = 215
PANORAMA_POSITION_LIFT = 535
PANORAMA_POSITION_TILT = 995
SAMPLE_POSITION_LIFT = 220
SAMPLE_POSITION_TILT = 240
PROBE_POSITION_LIFT = 950
PROBE_POSITION_TILT = 440
#####################################
# UbiquitiRadioSettings Class Definition
#####################################
class Mining(QtCore.QObject):
lift_position_update_ready__signal = QtCore.pyqtSignal(int)
tilt_position_update_ready__signal = QtCore.pyqtSignal(int)
weight_measurement_update_ready__signal = QtCore.pyqtSignal(int)
temp_update_ready__signal = QtCore.pyqtSignal(float)
moisture_update_ready__signal = QtCore.pyqtSignal(float)
loss_tangent_update_ready__signal = QtCore.pyqtSignal(float)
electrical_conductivity_update_ready__signal = QtCore.pyqtSignal(float)
real_dielectric_update_ready__signal = QtCore.pyqtSignal(float)
imaginary_dielectric_update_ready__signal = QtCore.pyqtSignal(float)
def __init__(self, shared_objects):
super(Mining, self).__init__()
# ########## Reference to class init variables ##########
self.shared_objects = shared_objects
self.left_screen = self.shared_objects["screens"]["left_screen"]
self.mining_qlcdnumber = self.left_screen.mining_qlcdnumber # type:QtWidgets.QLCDNumber
self.mining_zero_button = self.left_screen.mining_zero_button # type:QtWidgets.QPushButton
self.lift_position_progress_bar = self.left_screen.lift_position_progress_bar # type:QtWidgets.QProgressBar
self.tilt_position_progress_bar = self.left_screen.tilt_position_progress_bar # type:QtWidgets.QProgressBar
self.mining_measure_move_button = self.left_screen.mining_measure_move_button # type:QtWidgets.QPushButton
self.mining_transport_move_button = self.left_screen.mining_transport_move_button # type:QtWidgets.QPushButton
self.mining_scoop_move_button = self.left_screen.mining_scoop_move_button # type:QtWidgets.QPushButton
self.mining_panorama_button = self.left_screen.mining_panorama_button # type:QtWidgets.QPushButton
self.mining_sample_button = self.left_screen.mining_sample_button # type:QtWidgets.QPushButton
self.mining_probe_button = self.left_screen.mining_probe_button # type:QtWidgets.QPushButton
self.science_temp_lcd_number = self.left_screen.science_temp_lcd_number # type:QtWidgets.QLCDNumber
self.science_moisture_lcd_number = self.left_screen.science_moisture_lcd_number # type:QtWidgets.QLCDNumber
self.science_loss_tangent_lcd_number = self.left_screen.science_loss_tangent_lcd_number # type:QtWidgets.QLCDNumber
self.science_electrical_conductivity_lcd_number = self.left_screen.science_electrical_conductivity_lcd_number # type:QtWidgets.QLCDNumber
self.science_real_dielectric_lcd_number = self.left_screen.science_real_dielectric_lcd_number # type:QtWidgets.QLCDNumber
self.science_imaginary_dielectric_lcd_number = self.left_screen.science_imaginary_dielectric_lcd_number # type:QtWidgets.QLCDNumber
self.cam_lcd_output_button = self.left_screen.cam_lcd_output_button # type:QtWidgets.QPushButton
self.cam_network_output_button = self.left_screen.cam_network_output_button # type:QtWidgets.QPushButton
self.cam_zoom_in_button = self.left_screen.cam_zoom_in_button # type:QtWidgets.QPushButton
self.cam_zoom_out_button = self.left_screen.cam_zoom_out_button # type:QtWidgets.QPushButton
self.cam_full_zoom_in_button = self.left_screen.cam_full_zoom_in_button # type:QtWidgets.QPushButton
self.cam_full_zoom_out_button = self.left_screen.cam_full_zoom_out_button # type:QtWidgets.QPushButton
self.cam_shoot_button = self.left_screen.cam_shoot_button # type:QtWidgets.QPushButton
# ########## Get the settings instance ##########
self.settings = QtCore.QSettings()
# ########## Get the Pick And Plate instance of the logger ##########
self.logger = logging.getLogger("groundstation")
# ########## Thread Flags ##########
self.run_thread_flag = True
# ########## Class Variables ##########
self.mining_status_subscriber = rospy.Subscriber(MINING_STATUS_TOPIC, MiningStatusMessage,
self.mining_status_message_received__callback)
self.soil_probe_subscriber = rospy.Subscriber(SOIL_PROBE_TOPIC, SoilSensorStatusMessage, self.on_soil_probe_message_received__callback)
self.scale_measurement_subscriber = rospy.Subscriber(SCALE_MEASUREMENT_TOPIC, Float64, self.on_scale_measurement_received__callback)
self.mining_control_publisher = rospy.Publisher(MINING_CONTROL_TOPIC, MiningControlMessage, queue_size=1)
self.camera_control_publisher = rospy.Publisher(CAMERA_CONTROL_TOPIC, CameraControlMessage, queue_size=1)
self.current_scale_measurement = 0
self.scale_zero_offset = 0
self.connect_signals_and_slots()
def connect_signals_and_slots(self):
self.mining_zero_button.clicked.connect(self.on_mining_zero_clicked__slot)
self.mining_measure_move_button.clicked.connect(self.on_mining_move_measure_clicked__slot)
self.mining_transport_move_button.clicked.connect(self.on_mining_move_transport_clicked__slot)
self.mining_scoop_move_button.clicked.connect(self.on_mining_move_scoop_clicked__slot)
self.mining_panorama_button.clicked.connect(self.on_mining_move_panorama_clicked__slot)
self.mining_sample_button.clicked.connect(self.on_mining_move_sample_clicked__slot)
self.mining_probe_button.clicked.connect(self.on_mining_move_probe_clicked__slot)
self.tilt_position_update_ready__signal.connect(self.tilt_position_progress_bar.setValue)
self.lift_position_update_ready__signal.connect(self.lift_position_progress_bar.setValue)
self.weight_measurement_update_ready__signal.connect(self.mining_qlcdnumber.display)
self.temp_update_ready__signal.connect(self.science_temp_lcd_number.display)
self.moisture_update_ready__signal.connect(self.science_moisture_lcd_number.display)
self.loss_tangent_update_ready__signal.connect(self.science_loss_tangent_lcd_number.display)
self.electrical_conductivity_update_ready__signal.connect(self.science_electrical_conductivity_lcd_number.display)
self.real_dielectric_update_ready__signal.connect(self.science_real_dielectric_lcd_number.display)
self.imaginary_dielectric_update_ready__signal.connect(self.science_imaginary_dielectric_lcd_number.display)
self.cam_lcd_output_button.clicked.connect(self.on_cam_lcd_button_clicked__slot)
self.cam_network_output_button.clicked.connect(self.on_cam_network_button_clicked__slot)
self.cam_zoom_in_button.clicked.connect(self.on_cam_zoom_in_button_clicked__slot)
self.cam_zoom_out_button.clicked.connect(self.on_cam_zoom_out_button_clicked__slot)
self.cam_full_zoom_in_button.clicked.connect(self.on_cam_full_zoom_in_button_clicked__slot)
self.cam_full_zoom_out_button.clicked.connect(self.on_cam_full_zoom_out_button_clicked__slot)
self.cam_shoot_button.clicked.connect(self.on_cam_shoot_button_clicked__slot)
def on_mining_zero_clicked__slot(self):
self.scale_zero_offset = -self.current_scale_measurement
def on_mining_move_transport_clicked__slot(self):
message = MiningControlMessage()
message.tilt_set_absolute = TRAVEL_POSITION_TILT
message.lift_set_absolute = TRAVEL_POSITION_LIFT
message.cal_factor = -1
self.mining_control_publisher.publish(message)
def on_mining_move_measure_clicked__slot(self):
message = MiningControlMessage()
message.tilt_set_absolute = MEASURE_POSITION_TILT
message.lift_set_absolute = MEASURE_POSITION_LIFT
message.cal_factor = -1
self.mining_control_publisher.publish(message)
def on_mining_move_scoop_clicked__slot(self):
message = MiningControlMessage()
message.tilt_set_absolute = SCOOP_POSITION_TILT
message.lift_set_absolute = SCOOP_POSITION_LIFT
message.cal_factor = -1
self.mining_control_publisher.publish(message)
def on_mining_move_panorama_clicked__slot(self):
message = MiningControlMessage()
message.tilt_set_absolute = PANORAMA_POSITION_TILT
message.lift_set_absolute = PANORAMA_POSITION_LIFT
message.cal_factor = -1
self.mining_control_publisher.publish(message)
def on_mining_move_sample_clicked__slot(self):
message = MiningControlMessage()
message.tilt_set_absolute = SAMPLE_POSITION_TILT
message.lift_set_absolute = SAMPLE_POSITION_LIFT
message.cal_factor = -1
self.mining_control_publisher.publish(message)
def on_mining_move_probe_clicked__slot(self):
message = MiningControlMessage()
message.tilt_set_absolute = PROBE_POSITION_TILT
message.lift_set_absolute = PROBE_POSITION_LIFT
message.cal_factor = -1
self.mining_control_publisher.publish(message)
def on_cam_lcd_button_clicked__slot(self):
message = CameraControlMessage()
message.camera_mode = 1
self.camera_control_publisher.publish(message)
def on_cam_network_button_clicked__slot(self):
message = CameraControlMessage()
message.camera_mode = 2
self.camera_control_publisher.publish(message)
def on_cam_zoom_in_button_clicked__slot(self):
message = CameraControlMessage()
message.zoom_in = 1
self.camera_control_publisher.publish(message)
def on_cam_zoom_out_button_clicked__slot(self):
message = CameraControlMessage()
message.zoom_out = 1
self.camera_control_publisher.publish(message)
def on_cam_full_zoom_in_button_clicked__slot(self):
message = CameraControlMessage()
message.full_zoom_in = 1
self.camera_control_publisher.publish(message)
def on_cam_full_zoom_out_button_clicked__slot(self):
message = CameraControlMessage()
message.full_zoom_out = 1
self.camera_control_publisher.publish(message)
def on_cam_shoot_button_clicked__slot(self):
message = CameraControlMessage()
message.shoot = 1
self.camera_control_publisher.publish(message)
def mining_status_message_received__callback(self, status):
status = status # type:MiningStatusMessage
self.tilt_position_update_ready__signal.emit(status.tilt_position)
self.lift_position_update_ready__signal.emit(status.lift_position)
def on_soil_probe_message_received__callback(self, data):
self.temp_update_ready__signal.emit(data.temp_c)
self.moisture_update_ready__signal.emit(data.moisture)
self.loss_tangent_update_ready__signal.emit(data.loss_tangent)
self.electrical_conductivity_update_ready__signal.emit(data.soil_electrical_conductivity)
self.real_dielectric_update_ready__signal.emit(data.real_dielectric_permittivity)
self.imaginary_dielectric_update_ready__signal.emit(data.imaginary_dielectric_permittivity)
def on_scale_measurement_received__callback(self, data):
grams = data.data * 1000
self.current_scale_measurement = grams
self.weight_measurement_update_ready__signal.emit(grams + self.scale_zero_offset)

View File

@@ -0,0 +1,312 @@
# coding=utf-8
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore, QtWidgets
import logging
import rospy
from time import time
from rover_arm.msg import ArmControlMessage, ArmStatusMessage
from rover_control.msg import GripperControlMessage
#####################################
# Global Variables
#####################################
ARM_RELATIVE_CONTROL_TOPIC = "/rover_arm/control/relative"
ARM_ABSOLUTE_CONTROL_TOPIC = "/rover_arm/control/absolute"
ARM_STATUS_TOPIC = "/rover_arm/status"
GRIPPER_CONTROL_TOPIC = "/rover_control/gripper/control"
THREAD_HERTZ = 5
POSITIONAL_TOLERANCE = 0.02
# Order is [base, shoulder, elbow, roll, wrist_pitch, wrist_roll]
ARM_STOW_PROCEDURE = [
[0.0, -0.035, -0.28, 0.0, 0.0, 0.0], # Out in front of rover
[0.0, -0.035, -0.28, -0.25, 0.25, 0.0],
[0.0, -0.035, -0.5, -0.25, 0.25, 0.0],
[0.0, -0.25, -0.5, -0.25, 0.25, -0.25]
]
ARM_UNSTOW_PROCEDURE = [
[0.0, -0.25, -0.5, -0.25, 0.25, -0.25],
[0.0, -0.035, -0.5, -0.25, 0.25, 0.0],
[0.0, -0.035, -0.28, -0.25, 0.25, 0.0],
[0.0, -0.035, -0.28, 0.0, 0.0, 0.0]
]
APPROACH_O2 = [
[0.0, -0.035, -0.28, 0.0, 0.0, 0.0], # Out in front of rover
[0.0, 0.0485472094896, -0.273685193022, -0.00102834607876, -0.17200773156, 0], # Correct positioning out to left side of rover
[-0.436250296246, 0.0485472094896, -0.273685193022, -0.00102834607876, -0.17200773156, 0] # Directly positioned, ready to grip
]
APPROACH_BEACON = [
[0.0, -0.035, -0.28, 0.0, 0.0, 0.0], # Out in front of rover
[0.0, 0.0361371382336, -0.325145836608, -0.00731261537597, -0.129662333807, 0.0569339269566], # Correct positioning out to right side of rover
[0.458505849045, 0.0361371382336, -0.325145633259, -0.00731200471916, -0.131140162948, 0.0920117742056]
]
#####################################
# UbiquitiRadioSettings Class Definition
#####################################
class MiscArm(QtCore.QThread):
def __init__(self, shared_objects):
super(MiscArm, self).__init__()
# ########## Reference to class init variables ##########
self.shared_objects = shared_objects
self.left_screen = self.shared_objects["screens"]["left_screen"]
self.arm_control_upright_zeroed_button = self.left_screen.arm_control_upright_zeroed_button # type:QtWidgets.QPushButton
self.arm_controls_stow_arm_button = self.left_screen.arm_controls_stow_arm_button # type:QtWidgets.QPushButton
self.arm_controls_unstow_arm_button = self.left_screen.arm_controls_unstow_arm_button # type:QtWidgets.QPushButton
# ##### FIXME #####
# Remove these once the arm is fixed
self.arm_controls_stow_arm_button.setEnabled(False)
self.arm_controls_unstow_arm_button.setEnabled(False)
# #################
self.arm_controls_calibration_button = self.left_screen.arm_controls_calibration_button # type:QtWidgets.QPushButton
self.arm_controls_clear_faults_button = self.left_screen.arm_controls_clear_faults_button # type:QtWidgets.QPushButton
self.arm_controls_reset_motor_drivers_button = self.left_screen.arm_controls_reset_motor_drivers_button # type:QtWidgets.QPushButton
self.arm_controls_approach_o2_button = self.left_screen.arm_controls_approach_o2_button # type:QtWidgets.QPushButton
self.arm_controls_depart_o2_button = self.left_screen.arm_controls_depart_o2_button # type:QtWidgets.QPushButton
self.arm_controls_approach_beacon_button = self.left_screen.arm_controls_approach_beacon_button # type:QtWidgets.QPushButton
self.arm_controls_depart_beacon_button = self.left_screen.arm_controls_depart_beacon_button # type:QtWidgets.QPushButton
self.gripper_home_button = self.left_screen.gripper_home_button # type:QtWidgets.QPushButton
self.gripper_toggle_light_button = self.left_screen.gripper_toggle_light_button # type:QtWidgets.QPushButton
# ########## Get the settings instance ##########
self.settings = QtCore.QSettings()
# ########## Get the Pick And Plate instance of the logger ##########
self.logger = logging.getLogger("groundstation")
# ########## Thread Flags ##########
self.run_thread_flag = True
# ########## Class Variables ##########
self.wait_time = 1.0 / THREAD_HERTZ
self.arm_status_subscriber = rospy.Subscriber(ARM_STATUS_TOPIC, ArmStatusMessage,
self.new_arm_status_message_received__callback)
self.arm_relative_control_publisher = rospy.Publisher(ARM_RELATIVE_CONTROL_TOPIC, ArmControlMessage,
queue_size=1)
self.arm_absolute_control_publisher = rospy.Publisher(ARM_ABSOLUTE_CONTROL_TOPIC, ArmControlMessage,
queue_size=1)
self.gripper_control_publisher = rospy.Publisher(GRIPPER_CONTROL_TOPIC, GripperControlMessage, queue_size=1)
self.base_position = 0
self.shoulder_position = 0
self.elbow_position = 0
self.roll_position = 0
self.wrist_pitch_position = 0
self.wrist_roll_position = 0
self.should_stow_arm = False
self.should_unstow_arm = False
self.should_approach_o2 = False
self.should_depart_o2 = False
self.should_approach_beacon = False
self.should_depart_beacon = False
def run(self):
self.logger.debug("Starting MiscArm Thread")
while self.run_thread_flag:
start_time = time()
if self.should_stow_arm:
self.stow_rover_arm()
self.should_stow_arm = False
elif self.should_unstow_arm:
self.unstow_rover_arm()
self.should_unstow_arm = False
elif self.should_approach_o2:
self.approach_o2()
self.should_approach_o2 = False
elif self.should_depart_o2:
self.depart_o2()
self.should_depart_o2 = False
elif self.should_approach_beacon:
self.approach_beacon()
self.should_approach_beacon = False
elif self.should_depart_beacon:
self.depart_beacon()
self.should_depart_beacon = False
time_diff = time() - start_time
self.msleep(max(int(self.wait_time - time_diff), 0))
self.logger.debug("Stopping MiscArm Thread")
def stow_rover_arm(self):
for movement in ARM_STOW_PROCEDURE:
self.process_absolute_move_command(movement)
def unstow_rover_arm(self):
for movement in ARM_UNSTOW_PROCEDURE:
self.process_absolute_move_command(movement)
def approach_o2(self):
for movement in APPROACH_O2:
self.process_absolute_move_command(movement)
def depart_o2(self):
for movement in reversed(APPROACH_O2):
self.process_absolute_move_command(movement)
def approach_beacon(self):
for movement in APPROACH_BEACON:
self.process_absolute_move_command(movement)
def depart_beacon(self):
for movement in reversed(APPROACH_BEACON):
self.process_absolute_move_command(movement)
def process_absolute_move_command(self, movement):
message = ArmControlMessage()
message.base = movement[0]
message.shoulder = movement[1]
message.elbow = movement[2]
message.roll = movement[3]
message.wrist_pitch = movement[4]
message.wrist_roll = movement[5]
self.arm_absolute_control_publisher.publish(message)
self.wait_for_targets_reached(movement)
self.msleep(250)
def wait_for_targets_reached(self, movement):
base_set = movement[0]
shoulder_set = movement[1]
elbow_set = movement[2]
roll_set = movement[3]
wrist_pitch_set = movement[4]
wrist_roll_set = movement[5] - (wrist_pitch_set / 2.0)
while abs(self.base_position - base_set) > POSITIONAL_TOLERANCE:
# self.logger.debug("Waiting for base| %f\t%f" % (self.base_position, base_set))
self.msleep(10)
while abs(self.shoulder_position - shoulder_set) > POSITIONAL_TOLERANCE:
# self.logger.debug("Waiting for shoulder| %f\t%f" % (self.shoulder_position, shoulder_set))
self.msleep(10)
while abs(self.elbow_position - elbow_set) > POSITIONAL_TOLERANCE:
# self.logger.debug("Waiting for elbow| %f\t%f" % (self.elbow_position, elbow_set))
self.msleep(10)
while abs(self.roll_position - roll_set) > POSITIONAL_TOLERANCE:
# self.logger.debug("Waiting for roll| %f\t%f" % (self.roll_position, roll_set))
self.msleep(10)
while abs(self.wrist_pitch_position - wrist_pitch_set) > POSITIONAL_TOLERANCE:
# self.logger.debug("Waiting for wrist_pitch| %f\t%f" % (self.wrist_pitch_position, wrist_pitch_set))
self.msleep(10)
while abs(self.wrist_roll_position - wrist_roll_set) > POSITIONAL_TOLERANCE:
# self.logger.debug("Waiting for wrist_roll| %f\t%f" % (self.wrist_roll_position, wrist_roll_set))
self.msleep(10)
def connect_signals_and_slots(self):
self.arm_controls_stow_arm_button.clicked.connect(self.on_stow_arm_button_pressed__slot)
self.arm_controls_unstow_arm_button.clicked.connect(self.on_unstow_arm_button_pressed__slot)
self.arm_control_upright_zeroed_button.clicked.connect(self.on_upright_zeroed_button_pressed__slot)
self.arm_controls_calibration_button.clicked.connect(self.on_set_calibration_button_pressed__slot)
self.arm_controls_clear_faults_button.clicked.connect(self.on_clear_faults_button_pressed__slot)
self.arm_controls_reset_motor_drivers_button.clicked.connect(self.on_reset_drivers_button_pressed__slot)
self.arm_controls_approach_o2_button.clicked.connect(self.on_approach_o2_button_pressed__slot)
self.arm_controls_approach_beacon_button.clicked.connect(self.on_approach_beacon_button_pressed__slot)
self.gripper_home_button.clicked.connect(self.on_gripper_home_pressed)
self.gripper_toggle_light_button.clicked.connect(self.on_gripper_toggle_light_pressed)
def on_upright_zeroed_button_pressed__slot(self):
self.process_absolute_move_command([0 for _ in range(6)])
def on_set_calibration_button_pressed__slot(self):
message = ArmControlMessage()
message.calibrate = True
self.arm_relative_control_publisher.publish(message)
def on_clear_faults_button_pressed__slot(self):
message = ArmControlMessage()
message.clear_faults = True
self.arm_relative_control_publisher.publish(message)
def on_reset_drivers_button_pressed__slot(self):
message = ArmControlMessage()
message.reset_controllers = True
self.arm_relative_control_publisher.publish(message)
def on_stow_arm_button_pressed__slot(self):
self.should_stow_arm = True
def on_unstow_arm_button_pressed__slot(self):
self.should_unstow_arm = True
def on_approach_o2_button_pressed__slot(self):
self.should_approach_o2 = True
def on_depart_o2_button_pressed__slot(self):
self.should_depart_o2 = True
def on_approach_beacon_button_pressed__slot(self):
self.should_approach_beacon = True
def on_depart_beacon_button_pressed__slot(self):
self.should_depart_beacon = True
def on_gripper_home_pressed(self):
message = GripperControlMessage()
message.gripper_mode = 2
message.gripper_position_absolute = -1
message.should_home = True
self.gripper_control_publisher.publish(message)
def on_gripper_toggle_light_pressed(self):
message = GripperControlMessage()
message.gripper_mode = 2
message.toggle_light = True
message.gripper_position_absolute = -1
self.gripper_control_publisher.publish(message)
def new_arm_status_message_received__callback(self, data):
self.base_position = data.base
self.shoulder_position = data.shoulder
self.elbow_position = data.elbow
self.roll_position = data.roll
self.wrist_pitch_position = data.wrist_pitch
self.wrist_roll_position = data.wrist_roll
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
start_signal.connect(self.start)
signals_and_slots_signal.connect(self.connect_signals_and_slots)
kill_signal.connect(self.on_kill_threads_requested__slot)
def on_kill_threads_requested__slot(self):
self.run_thread_flag = False

View File

@@ -0,0 +1,166 @@
# coding=utf-8
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore, QtWidgets
import logging
import rospy
from time import time
import scipy.fftpack
import numpy
from std_msgs.msg import Float64MultiArray
#####################################
# Global Variables
#####################################
RDF_DATA_TOPIC = "/rover_science/rdf/data"
THREAD_HERTZ = 5
COLOR_GREEN = "background-color:darkgreen;"
COLOR_RED = "background-color:darkred;"
ALLOWED_RDF_VARIANCE = 0.15
#####################################
# UbiquitiRadioSettings Class Definition
#####################################
class RDF(QtCore.QThread):
rssi_lcd_number_update_ready__signal = QtCore.pyqtSignal(int)
beacon_lcd_number_update_ready__signal = QtCore.pyqtSignal(float)
beacon_valid_text_change_ready__signal = QtCore.pyqtSignal(str)
beacon_valid_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
def __init__(self, shared_objects):
super(RDF, self).__init__()
# ########## Reference to class init variables ##########
self.shared_objects = shared_objects
self.left_screen = self.shared_objects["screens"]["left_screen"]
self.rssi_lcdnumber = self.left_screen.rssi_lcdnumber # type:QtWidgets.QLCDNumber
self.beacon_frequency_lcd_number = self.left_screen.beacon_frequency_lcd_number # type:QtWidgets.QLCDNumber
self.beacon_frequency_valid_label = self.left_screen.beacon_frequency_valid_label # type:QtWidgets.QLCDNumber
# ########## Get the settings instance ##########
self.settings = QtCore.QSettings()
# ########## Get the Pick And Plate instance of the logger ##########
self.logger = logging.getLogger("groundstation")
# ########## Thread Flags ##########
self.run_thread_flag = True
# ########## Class Variables ##########
self.wait_time = 1.0 / THREAD_HERTZ
self.rdf_subscriber = rospy.Subscriber(RDF_DATA_TOPIC, Float64MultiArray, self.new_rdf_message_received__callback)
self.moving_average_raw_data = []
self.raw_data = numpy.array([])
self.raw_data_timestamps = numpy.array([])
self.data_window_size = 200
self.previous_frequencies = []
self.num_previous_frequencies = 3
def run(self):
self.logger.debug("Starting RDF Thread")
while self.run_thread_flag:
start_time = time()
temp = list(self.moving_average_raw_data)
if temp:
average = sum(temp) / len(temp)
self.rssi_lcd_number_update_ready__signal.emit(average)
if self.raw_data.size >= self.data_window_size and self.raw_data_timestamps.size >= self.data_window_size:
try:
time_step_array = numpy.array([])
for n in range(0, self.data_window_size - 1):
time_step_array = numpy.append(time_step_array, self.raw_data_timestamps[n + 1] - self.raw_data_timestamps[n])
T = numpy.average(time_step_array)
yf = scipy.fftpack.fft(self.raw_data)
xf = numpy.linspace(0.0, 1.0 / (2.0 * T), self.data_window_size / 2)
valid_range = []
for n in range(0, len(xf)):
if (xf[n] > 0.5) and (xf[n] <= 5.0):
valid_range.append(n)
yf = numpy.take(yf, valid_range)
xf = numpy.take(xf, valid_range)
max_index = numpy.argmax(numpy.abs(yf))
freq = xf[max_index]
if len(self.previous_frequencies) == self.num_previous_frequencies:
del self.previous_frequencies[0]
self.previous_frequencies.append(freq)
if len(self.previous_frequencies) == self.num_previous_frequencies:
variance_too_large = False
if abs(self.previous_frequencies[0] - self.previous_frequencies[1]) > ALLOWED_RDF_VARIANCE:
variance_too_large = True
if abs(self.previous_frequencies[0] - self.previous_frequencies[2]) > ALLOWED_RDF_VARIANCE:
variance_too_large = True
if abs(self.previous_frequencies[1] - self.previous_frequencies[2]) > ALLOWED_RDF_VARIANCE:
variance_too_large = True
self.beacon_valid_stylesheet_change_ready__signal.emit(COLOR_GREEN if not variance_too_large else COLOR_RED)
self.beacon_valid_text_change_ready__signal.emit("Yes" if not variance_too_large else "No")
self.beacon_lcd_number_update_ready__signal.emit(freq)
except Exception, e:
print e
self.raw_data = numpy.array([])
self.raw_data_timestamps = numpy.array([])
time_diff = time() - start_time
self.msleep(max(int(self.wait_time - time_diff), 0))
self.logger.debug("Stopping RDF Thread")
def new_rdf_message_received__callback(self, data):
if len(self.moving_average_raw_data) >= self.data_window_size:
del self.moving_average_raw_data[0]
self.moving_average_raw_data.append(data.data[0])
if self.raw_data.size != self.data_window_size and self.raw_data_timestamps.size != self.data_window_size:
self.raw_data = numpy.append(self.raw_data, data.data[0])
self.raw_data_timestamps = numpy.append(self.raw_data_timestamps, data.data[1])
def connect_signals_and_slots(self):
self.rssi_lcd_number_update_ready__signal.connect(self.rssi_lcdnumber.display)
self.beacon_lcd_number_update_ready__signal.connect(self.beacon_frequency_lcd_number.display)
self.beacon_valid_text_change_ready__signal.connect(self.beacon_frequency_valid_label.setText)
self.beacon_valid_stylesheet_change_ready__signal.connect(self.beacon_frequency_valid_label.setStyleSheet)
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
start_signal.connect(self.start)
signals_and_slots_signal.connect(self.connect_signals_and_slots)
kill_signal.connect(self.on_kill_threads_requested__slot)
def on_kill_threads_requested__slot(self):
self.run_thread_flag = False

View File

@@ -0,0 +1,182 @@
# coding=utf-8
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore, QtWidgets, QtGui
import logging
from time import time
import PIL.Image
from PIL.ImageQt import ImageQt
from random import random
import rospy
from tf import transformations
from scipy.interpolate import interp1d
import math
from sensor_msgs.msg import Imu
from Resources.Settings import MappingSettings as MappingSettings
#####################################
# Global Variables
#####################################
THREAD_HERTZ = 20
ROTATION_SPEED_MODIFIER = 2.5
IMU_DATA_TOPIC = "/rover_odometry/imu/data"
#####################################
# Controller Class Definition
#####################################
class SpeedAndHeadingIndication(QtCore.QThread):
show_compass_image__signal = QtCore.pyqtSignal()
heading_text_update_ready__signal = QtCore.pyqtSignal(str)
new_speed_update_ready__signal = QtCore.pyqtSignal(str)
pitch_update_ready__signal = QtCore.pyqtSignal(float)
roll_update_ready__signal = QtCore.pyqtSignal(float)
def __init__(self, shared_objects):
super(SpeedAndHeadingIndication, self).__init__()
# ########## Reference to class init variables ##########
self.shared_objects = shared_objects
self.right_screen = self.shared_objects["screens"]["right_screen"]
self.heading_compass_label = self.right_screen.heading_compass_label # type: QtWidgets.QLabel
self.heading_text_label = self.right_screen.current_heading_label # type: QtWidgets.QLabel
self.next_goal_label = self.right_screen.next_goal_label # type: QtWidgets.QLabel
self.current_speed_label = self.right_screen.current_speed_label # type: QtWidgets.QLabel
self.imu_pitch_lcd_number = self.right_screen.imu_pitch_lcd_number # type: QtWidgets.QLCDNumber
self.imu_roll_lcd_number = self.right_screen.imu_roll_lcd_number # type: QtWidgets.QLCDNumber
# ########## Get the settings instance ##########
self.settings = QtCore.QSettings()
# ########## Get the Pick And Plate instance of the logger ##########
self.logger = logging.getLogger("groundstation")
# ########## Thread Flags ##########
self.run_thread_flag = True
# ########## Class Variables ##########
self.wait_time = 1.0 / THREAD_HERTZ
self.main_compass_image = PIL.Image.open("Resources/Images/compass.png").resize((300, 300), PIL.Image.ANTIALIAS)
self.compass_pixmap = None
self.current_heading = 0
self.current_heading_changed = True
self.shown_heading = (self.current_heading + (1.5 * ROTATION_SPEED_MODIFIER)) % 360
self.current_heading_shown_rotation_angle = 0
self.last_current_heading_shown = -1000
self.rotation_direction = 1
self.imu_data = None
self.new_imu_data = False
self.yaw = None
self.pitch = None
self.roll = None
self.euler_interpolator = interp1d([math.pi, -math.pi], [-180, 180])
self.imu_data_subscriber = rospy.Subscriber(IMU_DATA_TOPIC, Imu, self.on_imu_data_received)
def run(self):
self.on_heading_changed__slot(self.current_heading)
while self.run_thread_flag:
start_time = time()
if self.new_imu_data:
self.calculate_euler_from_imu()
self.new_imu_data = False
if self.current_heading_changed:
self.update_heading_movement()
self.current_heading_changed = False
self.rotate_compass_if_needed()
time_diff = time() - start_time
self.msleep(max(int(self.wait_time - time_diff), 0))
def calculate_euler_from_imu(self):
quat = (
self.imu_data.orientation.x,
self.imu_data.orientation.y,
self.imu_data.orientation.z,
self.imu_data.orientation.w,
)
self.roll, self.pitch, self.yaw = transformations.euler_from_quaternion(quat)
self.current_heading = (self.euler_interpolator(self.yaw) + MappingSettings.DECLINATION_OFFSET) % 360
self.pitch_update_ready__signal.emit(self.pitch)
self.roll_update_ready__signal.emit(self.roll)
def rotate_compass_if_needed(self):
self.current_heading_shown_rotation_angle = int(self.current_heading)
if self.current_heading_shown_rotation_angle != self.last_current_heading_shown:
new_compass_image = self.main_compass_image.rotate(self.current_heading_shown_rotation_angle, resample=PIL.Image.BICUBIC)
self.last_current_heading_shown = self.current_heading_shown_rotation_angle
self.compass_pixmap = QtGui.QPixmap.fromImage(ImageQt(new_compass_image))
self.show_compass_image__signal.emit()
self.heading_text_update_ready__signal.emit(str(self.current_heading_shown_rotation_angle) + "°")
def update_heading_movement(self):
current_minus_shown = (self.current_heading - self.shown_heading) % 360
if current_minus_shown >= 180:
self.rotation_direction = -1
else:
self.rotation_direction = 1
def on_heading_changed__slot(self, new_heading):
self.current_heading = new_heading
self.heading_text_update_ready__signal.emit(str(new_heading) + "°")
self.current_heading_changed = True
def __on_heading_clicked__slot(self, event):
new_heading = self.current_heading
if event.button() == QtCore.Qt.LeftButton:
new_heading = (self.current_heading + 5) % 360
elif event.button() == QtCore.Qt.RightButton:
new_heading = (self.current_heading - 5) % 360
self.on_heading_changed__slot(new_heading)
self.new_speed_update_ready__signal.emit("%.2f" % (random() * 2.5))
self.heading_text_update_ready__signal.emit(str(new_heading) + "°")
def on_new_compass_image_ready__slot(self):
self.heading_compass_label.setPixmap(self.compass_pixmap)
def on_imu_data_received(self, data):
self.imu_data = data
self.new_imu_data = True
def connect_signals_and_slots(self):
self.show_compass_image__signal.connect(self.on_new_compass_image_ready__slot)
self.heading_text_update_ready__signal.connect(self.heading_text_label.setText)
self.heading_text_update_ready__signal.connect(self.next_goal_label.setText)
self.new_speed_update_ready__signal.connect(self.current_speed_label.setText)
self.heading_compass_label.mousePressEvent = self.__on_heading_clicked__slot
self.pitch_update_ready__signal.connect(self.imu_pitch_lcd_number.display)
self.roll_update_ready__signal.connect(self.imu_roll_lcd_number.display)
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
start_signal.connect(self.start)
signals_and_slots_signal.connect(self.connect_signals_and_slots)
kill_signal.connect(self.on_kill_threads_requested__slot)
def on_kill_threads_requested__slot(self):
self.run_thread_flag = False

View File

@@ -0,0 +1,324 @@
from PyQt5 import QtCore, QtWidgets, QtGui
import logging
import rospy
from sensor_msgs.msg import NavSatFix
GPS_POSITION_TOPIC = "/rover_odometry/fix"
class WaypointsCoordinator(QtCore.QThread):
new_manual_waypoint_entry = QtCore.pyqtSignal(str, float, float, int)
update_waypoint_entry = QtCore.pyqtSignal(str, str, str, int)
def __init__(self, shared_objects):
super(WaypointsCoordinator, self).__init__()
self.run_thread_flag = True
self.navigation_table_cur_click = None
self.landmark_table_cur_click = None
self.shared_objects = shared_objects
self.left_screen = self.shared_objects["screens"]["left_screen"]
self.navigation_label = (self.left_screen.
navigation_waypoints_table_widget)
self.landmark_label = self.left_screen.landmark_waypoints_table_widget
self.name_edit_label = self.left_screen.manual_waypoint_landmark_name_line_edit
self.latitude_label = self.left_screen.manual_waypoint_decimal_lattitude_spin_box
self.longitude_label = self.left_screen.manual_waypoint_decimal_longitude_spin_box
self.latitude_degree_label = self.left_screen.manual_waypoint_degrees_lattitude_spin_box
self.longitude_degree_label = self.left_screen.manual_waypoint_degrees_longitude_spin_box
self.latitude_minute_label = self.left_screen.manual_waypoint_minutes_lattitude_spin_box
self.longitude_minute_label = self.left_screen.manual_waypoint_minutes_longitude_spin_box
self.latitude_second_label = self.left_screen.manual_waypoint_seconds_lattitude_spin_box
self.longitude_second_label = self.left_screen.manual_waypoint_seconds_longitude_spin_box
self.latitude_card_label = self.left_screen.manual_waypoint_cardinal_lattitude_combo_box
self.longitude_card_label = self.left_screen.manual_waypoint_cardinal_longitude_combo_box
# Color Labels and Buttons
self.nav_color_label = self.left_screen.manual_waypoint_navigation_color_label
self.nav_color_set_button = self.left_screen.manual_waypoint_navigation_color_set_button
self.landmark_color_label = self.left_screen.manual_waypoint_landmark_color_label
self.landmark_color_set_button = self.left_screen.manual_waypoint_landmark_color_set_button
# Nav Table Buttons
self.nav_set_button_label = (self.left_screen.
navigation_waypoints_set_button)
self.nav_add_manual_button_label = (
self.left_screen.navigation_waypoints_add_manual_button)
self.nav_add_gps_button_label = (self.left_screen.
navigation_waypoints_add_gps_button)
self.nav_delete_button_label = (self.left_screen.
navigation_waypoints_delete_button)
# Land Table Buttons
self.land_set_button_label = (self.left_screen.
landmark_waypoints_set_button)
self.land_add_manual_button_label = (
self.left_screen.landmark_waypoints_add_manual_button)
self.land_add_gps_button_label = (self.left_screen.
landmark_waypoints_add_gps_button)
self.land_delete_button_label = (self.left_screen.
landmark_waypoints_delete_button)
self.settings = QtCore.QSettings()
self.logger = logging.getLogger("groundstation")
self.gps_position_subscriber = rospy.Subscriber(GPS_POSITION_TOPIC, NavSatFix,
self.gps_position_updated_callback)
self.longitude = None
self.latitude = None
self.nav_color = QtCore.Qt.yellow
self.landmark_color = QtCore.Qt.blue
self.nav_color_dialog = QtWidgets.QColorDialog()
self.nav_color_dialog.setWindowFlags(
QtCore.Qt.WindowStaysOnTopHint | QtCore.Qt.X11BypassWindowManagerHint | QtCore.Qt.WindowTitleHint | QtCore.Qt.WindowCloseButtonHint)
self.landmark_color_dialog = QtWidgets.QColorDialog()
self.landmark_color_dialog.setWindowFlags(
QtCore.Qt.WindowStaysOnTopHint | QtCore.Qt.X11BypassWindowManagerHint | QtCore.Qt.WindowTitleHint | QtCore.Qt.WindowCloseButtonHint)
def run(self):
while self.run_thread_flag:
self.msleep(3)
def connect_signals_and_slots(self):
self.new_manual_waypoint_entry.connect(self.update_manual_entry)
# setting up signals for Navigation Table
self.nav_add_gps_button_label.clicked.connect(self._nav_add_gps)
self.nav_delete_button_label.clicked.connect(self._nav_del)
self.nav_add_manual_button_label.clicked.connect(self._nav_add_manual)
self.nav_set_button_label.clicked.connect(self._nav_save)
# setting up signals for Landmark Table
self.land_add_gps_button_label.clicked.connect(self._land_add_gps)
self.land_delete_button_label.clicked.connect(self._land_del)
self.land_add_manual_button_label.clicked.connect(self.
_land_add_manual)
self.land_set_button_label.clicked.connect(self._land_save)
self.navigation_label.cellClicked.connect(self._on_nav_clicked)
self.landmark_label.cellClicked.connect(self._on_land_clicked)
self.nav_color_set_button.clicked.connect(self.nav_color_dialog.show)
self.landmark_color_set_button.clicked.connect(self.landmark_color_dialog.show)
self.nav_color_dialog.currentColorChanged.connect(self.__on_new_nav_color_selected)
self.landmark_color_dialog.currentColorChanged.connect(self.__on_new_landmark_color_selected)
def _add_to_table(self, name, lat, lng, color, table):
color_table_item = QtWidgets.QTableWidgetItem()
color_table_item.setBackground(color)
count = table.rowCount()
table.insertRow(count)
table.setItem(count, 0, QtWidgets.QTableWidgetItem(name))
table.setItem(count, 1, QtWidgets.QTableWidgetItem(lat))
table.setItem(count, 2, QtWidgets.QTableWidgetItem(lng))
table.setItem(count, 3, color_table_item)
def _clear_inputs(self):
self.name_edit_label.clear()
self.latitude_label.clear()
self.longitude_label.clear()
def _is_empty_inputs(self):
if not self.name_edit_label.text():
return True
if not self.latitude_label.text():
return True
if not self.longitude_label.text():
return True
return False
def _nav_add_gps(self):
if self.longitude and self.latitude:
name = self.navigation_label.rowCount()
self._add_to_table(str(name + 1), str(self.latitude),
str(self.longitude), self.nav_color,
self.navigation_label)
self._clear_inputs()
def _nav_save(self):
if not self._is_empty_inputs():
lat = self.latitude_label.text()
lng = self.longitude_label.text()
self.navigation_label.setItem(
self.navigation_table_cur_click,
1,
QtWidgets.QTableWidgetItem(lat))
self.navigation_label.setItem(
self.navigation_table_cur_click,
2,
QtWidgets.QTableWidgetItem(lng))
color_table_item = QtWidgets.QTableWidgetItem()
color_table_item.setBackground(self.nav_color)
self.navigation_label.setItem(
self.navigation_table_cur_click,
3,
color_table_item)
self._clear_inputs()
def _nav_add_manual(self):
# request GPS data
if not self._is_empty_inputs():
name = self.navigation_label.rowCount()
lat = self.latitude_label.text()
lng = self.longitude_label.text()
self._add_to_table(str(name + 1), lat,
lng, self.nav_color,
self.navigation_label)
self._clear_inputs()
def _nav_del(self):
if self.navigation_table_cur_click is not None:
self.navigation_label.removeRow(self.navigation_table_cur_click)
count = self.navigation_label.rowCount()
for x in range(self.navigation_table_cur_click, count):
self.navigation_label.setItem(x,
0,
QtWidgets.
QTableWidgetItem(str(x + 1)))
self._clear_inputs()
def _land_add_gps(self):
if self.longitude and self.latitude:
name = self.name_edit_label.text()
self._add_to_table(name, str(self.latitude), str(self.longitude), self.landmark_color, self.landmark_label)
self._clear_inputs()
def _land_add_manual(self):
if not self._is_empty_inputs():
name = self.name_edit_label.text()
lat = self.latitude_label.text()
lng = self.longitude_label.text()
self._add_to_table(name, lat,
lng, self.landmark_color,
self.landmark_label)
self._clear_inputs()
def _land_del(self):
if self.landmark_table_cur_click is not None:
self.landmark_label.removeRow(self.landmark_table_cur_click)
count = self.landmark_label.rowCount()
for x in range(self.landmark_table_cur_click, count):
self.navigation_label.setItem(x,
0,
QtWidgets.
QTableWidgetItem(str(x + 1)))
self._clear_inputs()
def _land_save(self):
if not self._is_empty_inputs():
name = self.name_edit_label.text()
lat = self.latitude_label.text()
lng = self.longitude_label.text()
self.landmark_label.setItem(self.landmark_table_cur_click, 0,
QtWidgets.QTableWidgetItem(name))
self.landmark_label.setItem(self.landmark_table_cur_click, 1,
QtWidgets.QTableWidgetItem(lat))
self.landmark_label.setItem(self.landmark_table_cur_click, 2,
QtWidgets.QTableWidgetItem(lng))
color_table_item = QtWidgets.QTableWidgetItem()
color_table_item.setBackground(self.landmark_color)
self.landmark_label.setItem(self.landmark_table_cur_click, 3,
color_table_item)
self._clear_inputs()
def setup_signals(self, start_signal,
signals_and_slots_signal, kill_signal):
start_signal.connect(self.start)
signals_and_slots_signal.connect(self.connect_signals_and_slots)
kill_signal.connect(self.on_kill_threads_requested_slot)
def on_kill_threads_requested_slot(self):
self.run_thread_flag = False
def update_manual_entry(self, name, lat, lng, table):
self.name_edit_label.setEnabled(bool(table))
self.name_edit_label.setText(name)
self.latitude_label.setValue(lat)
self.longitude_label.setValue(lng)
lat_d = float(abs(int(lat)))
lat_m = float(int((abs(lat) - lat_d) * 60))
lat_s = ((abs(lat) - lat_d - (lat_m / 60.0)) * 3600.)
if lat > 0.:
self.latitude_card_label.setCurrentText("N")
else:
self.latitude_card_label.setCurrentText("S")
self.latitude_degree_label.setValue(lat_d)
self.latitude_minute_label.setValue(lat_m)
self.latitude_second_label.setValue(lat_s)
lng_d = float(abs(int(lng)))
lng_m = float(int((abs(lng) - lng_d) * 60))
lng_s = ((abs(lng) - lng_d - (lng_m / 60.0)) * 3600.)
if lng > 0.:
self.longitude_card_label.setCurrentText("E")
else:
self.longitude_card_label.setCurrentText("W")
self.longitude_degree_label.setValue(lng_d)
self.longitude_minute_label.setValue(lng_m)
self.longitude_second_label.setValue(lng_s)
def _on_nav_clicked(self, row, col):
self.navigation_table_cur_click = row
self.landmark_table_cur_click = None
self.new_manual_waypoint_entry.emit(
self.navigation_label.item(row, 0).text(),
float(self.navigation_label.item(row, 1).text()),
float(self.navigation_label.item(row, 2).text()),
0
)
def _on_land_clicked(self, row, col):
self.landmark_table_cur_click = row
self.navigation_table_cur_click = None
self.new_manual_waypoint_entry.emit(
self.landmark_label.item(row, 0).text(),
float(self.landmark_label.item(row, 1).text()),
float(self.landmark_label.item(row, 2).text()),
1
)
def __on_new_nav_color_selected(self, color):
self.nav_color_label.setStyleSheet(
"background-color: rgb(%s, %s, %s)" % (color.red(), color.green(), color.blue()))
self.nav_color = color
def __on_new_landmark_color_selected(self, color):
self.landmark_color_label.setStyleSheet(
"background-color: rgb(%s, %s, %s)" % (color.red(), color.green(), color.blue()))
self.landmark_color = color
def gps_position_updated_callback(self, data):
self.latitude = data.latitude
self.longitude = data.longitude

View File

@@ -0,0 +1,125 @@
# coding=utf-8
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore, QtWidgets
import logging
from time import time
import paramiko
#####################################
# Global Variables
#####################################
THREAD_HERTZ = 5
ACCESS_POINT_IP = "192.168.1.20" # The channel only has to be set on the access point. The staion will adjust.
ACCESS_POINT_USER = "ubnt"
ACCESS_POINT_PASSWORD = "rover4lyfe^" # We don't care about this password, don't freak out. Wifi is open anyways...
GET_CURRENT_CHANNEL_COMMAND = "iwlist ath0 channel"
SET_CHANNEL_COMMAND = "iwconfig ath0 channel"
#####################################
# UbiquitiRadioSettings Class Definition
#####################################
class UbiquitiRadioSettings(QtCore.QThread):
show_channel__signal = QtCore.pyqtSignal(int)
set_gui_elements_enabled__signal = QtCore.pyqtSignal(bool)
def __init__(self, shared_objects):
super(UbiquitiRadioSettings, self).__init__()
# ########## Reference to class init variables ##########
self.shared_objects = shared_objects
self.left_screen = self.shared_objects["screens"]["left_screen"]
self.ubiquiti_channel_spin_box = self.left_screen.ubiquiti_channel_spin_box # type: QtWidgets.QSpinBox
self.ubiquiti_channel_apply_button = self.left_screen.ubiquiti_channel_apply_button # type: QtWidgets.QPushButton
# ########## Get the settings instance ##########
self.settings = QtCore.QSettings()
# ########## Get the Pick And Plate instance of the logger ##########
self.logger = logging.getLogger("groundstation")
# ########## Thread Flags ##########
self.run_thread_flag = True
# ########## Class Variables ##########
self.wait_time = 1.0 / THREAD_HERTZ
self.channel_change_needed = False
self.new_channel = 0
self.ssh_client = None
def run(self):
self.set_gui_elements_enabled__signal.emit(False)
try:
self.setup_and_connect_ssh_client()
except Exception:
return
self.get_and_show_current_channel()
while self.run_thread_flag:
start_time = time()
self.apply_channel_if_needed()
time_diff = time() - start_time
self.msleep(max(int(self.wait_time - time_diff), 0))
def setup_and_connect_ssh_client(self):
self.ssh_client = paramiko.SSHClient()
self.ssh_client.set_missing_host_key_policy(paramiko.AutoAddPolicy())
self.ssh_client.connect(ACCESS_POINT_IP, username=ACCESS_POINT_USER, password=ACCESS_POINT_PASSWORD,
compress=True)
def apply_channel_if_needed(self):
if self.channel_change_needed:
self.show_channel__signal.emit(0)
self.set_gui_elements_enabled__signal.emit(False)
self.ssh_client.exec_command(SET_CHANNEL_COMMAND + " %02d" % self.new_channel)
self.get_and_show_current_channel()
self.channel_change_needed = False
def get_and_show_current_channel(self):
channel = 0
ssh_stdin, ssh_stdout, ssh_stderr = self.ssh_client.exec_command(GET_CURRENT_CHANNEL_COMMAND)
output = ssh_stdout.read()
for line in output.split("\n"):
if "Current Frequency:" in line:
channel = line.strip("()").split("Channel ")[1]
break
self.msleep(500) # From the gui, this helps show something is actually happening
self.show_channel__signal.emit(int(channel))
self.set_gui_elements_enabled__signal.emit(True)
def on_ubiquiti_channel_apply_pressed__slot(self):
self.new_channel = self.ubiquiti_channel_spin_box.value()
self.channel_change_needed = True
def connect_signals_and_slots(self):
self.ubiquiti_channel_apply_button.clicked.connect(self.on_ubiquiti_channel_apply_pressed__slot)
self.show_channel__signal.connect(self.ubiquiti_channel_spin_box.setValue)
self.set_gui_elements_enabled__signal.connect(self.ubiquiti_channel_spin_box.setEnabled)
self.set_gui_elements_enabled__signal.connect(self.ubiquiti_channel_apply_button.setEnabled)
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
start_signal.connect(self.start)
signals_and_slots_signal.connect(self.connect_signals_and_slots)
kill_signal.connect(self.on_kill_threads_requested__slot)
def on_kill_threads_requested__slot(self):
self.run_thread_flag = False

View File

@@ -0,0 +1,45 @@
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore, QtGui, QtWidgets
import time
import logging
import socket
import rospy
# Custom Imports
#####################################
# Global Variables
#####################################
#####################################
# RoverVideoReceiver Class Definition
#####################################
class ROSMasterChecker(QtCore.QThread):
def __init__(self):
super(ROSMasterChecker, self).__init__()
# ########## Class Variables ##########
self.ros_master_present = False
self.start_time = time.time()
self.start()
def run(self):
try:
master = rospy.get_master()
master.getPid()
self.ros_master_present = True
except socket.error:
return
def master_present(self, timeout):
while self.isRunning() and (time.time() - self.start_time) < timeout:
self.msleep(100)
return self.ros_master_present

View File

@@ -0,0 +1,338 @@
#!/usr/bin/env python
# coding=utf-8
import rospy
from rover_status.msg import *
from PyQt5 import QtWidgets, QtCore, QtGui, uic
from std_msgs.msg import Empty
import PIL.Image
from PIL.ImageQt import ImageQt
import time
from std_msgs.msg import UInt16
# import Timer
REQUEST_UPDATE_TOPIC = "/rover_status/update_requested"
CAMERA_TOPIC_NAME = "/rover_status/camera_status"
BOGIE_TOPIC_NAME = "/rover_status/bogie_status"
FRSKY_TOPIC_NAME = "/rover_status/frsky_status"
GPS_TOPIC_NAME = "/rover_status/gps_status"
JETSON_TOPIC_NAME = "/rover_status/jetson_status"
MISC_TOPIC_NAME = "/rover_status/misc_status"
BATTERY_TOPIC_NAME = "/rover_status/battery_status"
CO2_TOPIC_NAME = "/rover_control/tower/status/co2"
COLOR_GREEN = "background-color: darkgreen; border: 1px solid black;"
COLOR_ORANGE = "background-color: orange; border: 1px solid black;"
COLOR_YELLOW = "background-color: rgb(204,204,0); border: 1px solid black; color: black;"
COLOR_RED = "background-color: darkred; border: 1px solid black;"
GPS_BEST_CASE_ACCURACY = 3
LOW_BATTERY_DIALOG_TIMEOUT = 120
CRITICAL_BATTERY_DIALOG_TIMEOUT = 30
class SensorCore(QtCore.QThread):
# ########## create signals for slots ##########
jetson_cpu_update_ready__signal = QtCore.pyqtSignal(str)
jetson_cpu_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
jetson_emmc_update_ready__signal = QtCore.pyqtSignal(str)
jetson_emmc_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
jetson_gpu_temp_update_ready__signal = QtCore.pyqtSignal(str)
jetson_gpu_temp_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
jetson_ram_update_ready__signal = QtCore.pyqtSignal(str)
jetson_ram_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
bogie_connection_1_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
bogie_connection_2_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
bogie_connection_3_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
gps_fix_update_ready__signal = QtCore.pyqtSignal(str)
gps_heading_valid_update_ready__signal = QtCore.pyqtSignal(str)
gps_num_satellites_update_ready__signal = QtCore.pyqtSignal(str)
gps_accuracy_update_ready__signal = QtCore.pyqtSignal(str)
co2_levels_update_ready__signal = QtCore.pyqtSignal(str)
camera_zed_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
camera_under_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
camera_chassis_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
camera_main_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
gps_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
frsky_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
battery_voltage_update_ready__signal = QtCore.pyqtSignal(str)
battery_voltage_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
show_battery_low__signal = QtCore.pyqtSignal()
show_battery_critical__signal = QtCore.pyqtSignal()
def __init__(self, shared_objects):
super(SensorCore, self).__init__()
self.run_thread_flag = True
# ########## Reference to class init variables ##########
self.shared_objects = shared_objects
self.screen_main_window = self.shared_objects["screens"]["left_screen"]
# self.cpu_read = self.screen_main_window.lineEdit # type: QtWidgets.QLabel
# self.ram_read = self.screen_main_window.lineEdit_2 # type: QtWidgets.QLabel
# ########## set vars to gui elements
self.osurc_logo_label = self.screen_main_window.osurc_logo_label # type: QtWidgets.QLabel
self.rover_conn = self.screen_main_window.rover # type: QtWidgets.QLabel
self.frsky = self.screen_main_window.frsky # type: QtWidgets.QLabel
self.nav_mouse = self.screen_main_window.nav_mouse # type: QtWidgets.QLabel
self.joystick = self.screen_main_window.joystick # type: QtWidgets.QLabel
self.gps_fix_label = self.screen_main_window.gps_fix_label # type: QtWidgets.QLabel
self.gps_heading_valid_label = self.screen_main_window.gps_heading_valid_label # type: QtWidgets.QLabel
self.gps_num_satellites_label = self.screen_main_window.gps_num_satellites_label # type: QtWidgets.QLabel
self.gps_accuracy_label = self.screen_main_window.gps_accuracy_label # type: QtWidgets.QLabel
self.zed = self.screen_main_window.zed # type: QtWidgets.QLabel
self.main_cam = self.screen_main_window.main_cam # type: QtWidgets.QLabel
self.chassis_cam = self.screen_main_window.chassis_cam # type: QtWidgets.QLabel
self.under_cam = self.screen_main_window.under_cam # type: QtWidgets.QLabel
self.clock = self.screen_main_window.clock_qlcdnumber # type: QtWidgets.QLCDNumber
self.cpu = self.screen_main_window.cpu # type: QtWidgets.QLabel
self.ram = self.screen_main_window.ram # type: QtWidgets.QLabel
self.gpu_temp = self.screen_main_window.gpu_temp # type: QtWidgets.QLabel
self.emmc = self.screen_main_window.emmc # type: QtWidgets.QLabel
self.battery = self.screen_main_window.battery_voltage_status_label # type: QtWidgets.QLabel
self.co2_levels_label = self.screen_main_window.co2_levels_label # type: QtWidgets.QLabel
# ########## subscriptions pulling data from system_statuses_node.py ##########
self.camera_status = rospy.Subscriber(CAMERA_TOPIC_NAME, CameraStatuses, self.__camera_callback)
self.frsky_status = rospy.Subscriber(FRSKY_TOPIC_NAME, FrSkyStatus, self.__frsky_callback)
self.gps_status = rospy.Subscriber(GPS_TOPIC_NAME, GPSInfo, self.__gps_callback)
self.jetson_status = rospy.Subscriber(JETSON_TOPIC_NAME, JetsonInfo, self.__jetson_callback)
self.misc_status = rospy.Subscriber(MISC_TOPIC_NAME, MiscStatuses, self.__misc_callback)
self.battery_status = rospy.Subscriber(BATTERY_TOPIC_NAME, BatteryStatusMessage, self.__battery_callback)
self.co2_status = rospy.Subscriber(CO2_TOPIC_NAME, UInt16, self.__co2_callback)
self.camera_msg = CameraStatuses()
self.bogie_msg = None # BogieStatuses()
self.FrSky_msg = FrSkyStatus()
self.GPS_msg = GPSInfo()
self.jetson_msg = JetsonInfo()
self.misc_msg = MiscStatuses()
self.battery_msg = BatteryStatusMessage()
self.update_requester = rospy.Publisher(REQUEST_UPDATE_TOPIC, Empty, queue_size=10)
# Apply OSURC Logo
self.osurc_logo_pil = PIL.Image.open("Resources/Images/osurclogo.png").resize((210, 75), PIL.Image.BICUBIC)
self.osurc_logo_pixmap = QtGui.QPixmap.fromImage(ImageQt(self.osurc_logo_pil))
self.osurc_logo_label.setPixmap(self.osurc_logo_pixmap) # Init should be in main thread, should be fine
self.low_battery_warning_dialog = QtWidgets.QMessageBox()
self.low_battery_warning_dialog.setIcon(QtWidgets.QMessageBox.Warning)
self.low_battery_warning_dialog.setText("\n\n\n\nRover battery low!\nReturn and charge soon to avoid battery damage!\n\n\n\n")
self.low_battery_warning_dialog.setWindowTitle("Low Battery")
self.low_battery_warning_dialog.setStandardButtons(QtWidgets.QMessageBox.Ok)
self.low_battery_warning_dialog.setWindowFlags(
QtCore.Qt.WindowStaysOnTopHint | QtCore.Qt.X11BypassWindowManagerHint | QtCore.Qt.WindowTitleHint | QtCore.Qt.WindowCloseButtonHint)
self.low_battery_warning_dialog.setStyleSheet(COLOR_YELLOW)
self.critical_battery_warning_dialog = QtWidgets.QMessageBox()
self.critical_battery_warning_dialog.setIcon(QtWidgets.QMessageBox.Critical)
self.critical_battery_warning_dialog.setText(
"\n\n\n\nRover battery critical!\nPower down immediately or battery damage will occur!\n\n\n\n")
self.critical_battery_warning_dialog.setWindowTitle("Critical Battery")
self.critical_battery_warning_dialog.setStandardButtons(QtWidgets.QMessageBox.Ok)
self.critical_battery_warning_dialog.setWindowFlags(
QtCore.Qt.WindowStaysOnTopHint | QtCore.Qt.X11BypassWindowManagerHint | QtCore.Qt.WindowTitleHint | QtCore.Qt.WindowCloseButtonHint)
self.critical_battery_warning_dialog.setStyleSheet(COLOR_RED)
self.low_battery_warning_last_shown = 0
self.critical_battery_warning_last_shown = 0
def __camera_callback(self, data):
self.camera_msg.camera_zed = data.camera_zed
self.camera_msg.camera_undercarriage = data.camera_undercarriage
self.camera_msg.camera_chassis = data.camera_chassis
self.camera_msg.camera_main_navigation = data.camera_main_navigation
if data.camera_zed is False:
# self.zed.setStyleSheet("background-color: red;")
self.camera_zed_stylesheet_change_ready__signal.emit(COLOR_RED)
else:
# self.zed.setStyleSheet(COLOR_GREEN)
self.camera_zed_stylesheet_change_ready__signal.emit(COLOR_GREEN)
if data.camera_undercarriage is False:
# self.under_cam.setStyleSheet(COLOR_RED)
self.camera_under_stylesheet_change_ready__signal.emit(COLOR_RED)
else:
# self.under_cam.setStyleSheet(COLOR_GREEN)
self.camera_under_stylesheet_change_ready__signal.emit(COLOR_GREEN)
if data.camera_chassis is False:
# self.chassis_cam.setStyleSheet(COLOR_RED)
self.camera_chassis_stylesheet_change_ready__signal.emit(COLOR_RED)
else:
# self.chassis_cam.setStyleSheet(COLOR_GREEN)
self.camera_chassis_stylesheet_change_ready__signal.emit(COLOR_GREEN)
if data.camera_main_navigation is False:
# self.main_cam.setStyleSheet(COLOR_RED)
self.camera_main_stylesheet_change_ready__signal.emit(COLOR_RED)
else:
# self.main_cam.setStyleSheet(COLOR_GREEN)
self.camera_main_stylesheet_change_ready__signal.emit(COLOR_GREEN)
def __frsky_callback(self, data):
self.FrSky_msg.FrSky_controller_connection_status = data.FrSky_controller_connection_status
if self.FrSky_msg.FrSky_controller_connection_status is False:
self.frsky_stylesheet_change_ready__signal.emit(COLOR_RED)
else:
self.frsky_stylesheet_change_ready__signal.emit(COLOR_GREEN)
def __jetson_callback(self, data):
self.jetson_cpu_update_ready__signal.emit("TX2 CPU\n" + str(data.jetson_CPU) + " %")
if data.jetson_CPU > 85:
self.jetson_cpu_stylesheet_change_ready__signal.emit(COLOR_ORANGE)
elif data.jetson_CPU > 95:
self.jetson_cpu_stylesheet_change_ready__signal.emit(COLOR_RED)
else:
self.jetson_cpu_stylesheet_change_ready__signal.emit(COLOR_GREEN)
self.jetson_ram_update_ready__signal.emit("TX2 RAM\n" + str(data.jetson_RAM) + " %")
if data.jetson_RAM > 79:
self.jetson_ram_stylesheet_change_ready__signal.emit(COLOR_ORANGE)
elif data.jetson_RAM > 89:
self.jetson_ram_stylesheet_change_ready__signal.emit(COLOR_RED)
else:
self.jetson_ram_stylesheet_change_ready__signal.emit(COLOR_GREEN)
self.jetson_gpu_temp_update_ready__signal.emit("TX2 TEMP\n" + str(data.jetson_GPU_temp) + " °C")
if data.jetson_GPU_temp > 64:
self.jetson_gpu_temp_stylesheet_change_ready__signal.emit(COLOR_ORANGE)
elif data.jetson_GPU_temp > 79:
self.jetson_gpu_temp_stylesheet_change_ready__signal.emit(COLOR_RED)
else:
self.jetson_gpu_temp_stylesheet_change_ready__signal.emit(COLOR_GREEN)
self.jetson_emmc_update_ready__signal.emit("TX2 EMMC\n" + str(data.jetson_EMMC) + " %")
if data.jetson_EMMC > 79:
self.jetson_emmc_stylesheet_change_ready__signal.emit(COLOR_ORANGE)
elif data.jetson_EMMC > 89:
self.jetson_emmc_stylesheet_change_ready__signal.emit(COLOR_RED)
else:
self.jetson_emmc_stylesheet_change_ready__signal.emit(COLOR_GREEN)
def __gps_callback(self, data):
if data.gps_connected:
self.gps_fix_update_ready__signal.emit("GPS Fix\nTrue")
self.gps_stylesheet_change_ready__signal.emit(COLOR_GREEN)
else:
self.gps_stylesheet_change_ready__signal.emit(COLOR_RED)
self.gps_fix_update_ready__signal.emit("GPS Fix\nFalse")
if data.gps_heading != -1:
self.gps_heading_valid_update_ready__signal.emit("GPS Heading Valid\nTrue")
else:
self.gps_heading_valid_update_ready__signal.emit("GPS Heading Valid\nFalse")
self.gps_num_satellites_update_ready__signal.emit("GPS Satellites\n%s" % data.num_satellites)
self.gps_accuracy_update_ready__signal.emit(
"GPS Accuracy\n%2.2f m" % (data.horizontal_dilution * GPS_BEST_CASE_ACCURACY))
def __misc_callback(self, data):
self.misc_msg.arm_connection_status = data.arm_connection_status
self.misc_msg.arm_end_effector_connection_statuses = data.arm_end_effector_connection_statuses
self.misc_msg.sample_containment_connection_status = data.sample_containment_connection_status
self.misc_msg.tower_connection_status = data.tower_connection_status
self.misc_msg.chassis_pan_tilt_connection_status = data.chassis_pan_tilt_connection_status
def __battery_callback(self, data):
voltage = data.battery_voltage / 1000.0
if voltage >= 21:
self.battery_voltage_stylesheet_change_ready__signal.emit(COLOR_GREEN)
elif voltage >= 19:
self.battery_voltage_stylesheet_change_ready__signal.emit(COLOR_YELLOW)
if (time.time() - self.low_battery_warning_last_shown) > LOW_BATTERY_DIALOG_TIMEOUT:
self.show_battery_low__signal.emit()
self.low_battery_warning_last_shown = time.time()
else:
self.battery_voltage_stylesheet_change_ready__signal.emit(COLOR_RED)
if (time.time() - self.critical_battery_warning_last_shown) > CRITICAL_BATTERY_DIALOG_TIMEOUT:
self.show_battery_critical__signal.emit()
self.critical_battery_warning_last_shown = time.time()
self.battery_voltage_update_ready__signal.emit("Battery Voltage\n" + str(voltage) + " V")
def __co2_callback(self, data):
if data.data != 9999:
self.co2_levels_update_ready__signal.emit("CO2 Levels\n%d ppm" % data.data)
else:
self.co2_levels_update_ready__signal.emit("CO2 Levels\n--- ppm")
def __display_time(self):
time = QtCore.QTime.currentTime()
temp = time.toString('hh:mm')
self.clock.display(temp)
def run(self):
while self.run_thread_flag:
# self.update_requester.publish(Empty())
self.__display_time()
self.msleep(1000)
def connect_signals_and_slots(self):
self.jetson_cpu_update_ready__signal.connect(self.cpu.setText)
self.jetson_cpu_stylesheet_change_ready__signal.connect(self.cpu.setStyleSheet)
self.jetson_ram_update_ready__signal.connect(self.ram.setText)
self.jetson_ram_stylesheet_change_ready__signal.connect(self.ram.setStyleSheet)
self.jetson_emmc_update_ready__signal.connect(self.emmc.setText)
self.jetson_emmc_stylesheet_change_ready__signal.connect(self.emmc.setStyleSheet)
self.jetson_gpu_temp_update_ready__signal.connect(self.gpu_temp.setText)
self.jetson_gpu_temp_stylesheet_change_ready__signal.connect(self.gpu_temp.setStyleSheet)
self.camera_zed_stylesheet_change_ready__signal.connect(self.zed.setStyleSheet)
self.camera_under_stylesheet_change_ready__signal.connect(self.under_cam.setStyleSheet)
self.camera_chassis_stylesheet_change_ready__signal.connect(self.chassis_cam.setStyleSheet)
self.camera_main_stylesheet_change_ready__signal.connect(self.main_cam.setStyleSheet)
self.gps_stylesheet_change_ready__signal.connect(self.gps_fix_label.setStyleSheet)
self.frsky_stylesheet_change_ready__signal.connect(self.frsky.setStyleSheet)
self.gps_fix_update_ready__signal.connect(self.gps_fix_label.setText)
self.gps_heading_valid_update_ready__signal.connect(self.gps_heading_valid_label.setText)
self.gps_num_satellites_update_ready__signal.connect(self.gps_num_satellites_label.setText)
self.gps_accuracy_update_ready__signal.connect(self.gps_accuracy_label.setText)
self.co2_levels_update_ready__signal.connect(self.co2_levels_label.setText)
self.battery_voltage_update_ready__signal.connect(self.battery.setText)
self.battery_voltage_stylesheet_change_ready__signal.connect(self.battery.setStyleSheet)
self.show_battery_low__signal.connect(self.low_battery_warning_dialog.show)
self.show_battery_critical__signal.connect(self.critical_battery_warning_dialog.show)
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
start_signal.connect(self.start)
signals_and_slots_signal.connect(self.connect_signals_and_slots)
kill_signal.connect(self.on_kill_threads_requested__slot)
def on_kill_threads_requested__slot(self):
self.run_thread_flag = False
if __name__ == '__main__':
rover_statuses = SensorCore()
rover_statuses.run()

View File

@@ -0,0 +1,70 @@
#!/usr/bin/env python2
import sys
from PyQt5 import Qt
from PyQt5 import QtCore
from PyQt5.uic import loadUi
# [ms]
TICK_TIME = 2**6
class Timer(Qt.QMainWindow):
def __init__(self):
super(Timer, self).__init__()
# self.reset.clicked.connect(self.do_reset)
# self.start.clicked.connect(self.do_start)
self.timer = Qt.QTimer()
self.timer.setInterval(TICK_TIME)
self.timer.timeout.connect(self.tick)
self.running = False;
self.do_reset()
def __start_stop_reset_event(self, event):
if event.button() == QtCore.Qt.LeftButton:
if self.running is False:
self.do_start
elif self.running is True:
self.do_pause
elif event.button() == QtCore.Qt.RightButton:
self.do_reset
def display(self):
self.timer.display("%d:%05.2f" % (self.time // 60, self.time % 60))
@Qt.pyqtSlot()
def tick(self):
self.time += TICK_TIME/1000
self.display()
@Qt.pyqtSlot()
def do_start(self):
self.timer.start()
# self.start.setText("Pause")
# self.start.clicked.disconnect()
# self.start.clicked.connect(self.do_pause)
@Qt.pyqtSlot()
def do_pause(self):
self.timer.stop()
# self.start.setText("Start")
# self.start.clicked.disconnect()
# self.start.clicked.connect(self.do_start)
@Qt.pyqtSlot()
def do_reset(self):
self.time = 0
self.display()
app = Qt.QApplication(sys.argv)
timer = Timer()
timer.show()
app.exec_()

View File

@@ -0,0 +1,126 @@
# coding=utf-8
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore, QtWidgets
import logging
from time import time
import paramiko
from pprint import pprint
import json
#####################################
# Global Variables
#####################################
THREAD_HERTZ = 5
ACCESS_POINT_IP = "192.168.1.20" # The channel only has to be set on the access point. The staion will adjust.
ACCESS_POINT_USER = "ubnt"
ACCESS_POINT_PASSWORD = "rover4lyfe^" # We don't care about this password, don't freak out. Wifi is open anyways...
GENERAL_WIRELESS_INFO_COMMAND = "wstalist"
#####################################
# UbiquitiRadioSettings Class Definition
#####################################
class UbiquitiStatus(QtCore.QThread):
connection_quality_update_ready__signal = QtCore.pyqtSignal(str)
successful_transmission_update_ready__signal = QtCore.pyqtSignal(str)
radio_rates_update_ready__signal = QtCore.pyqtSignal(str)
radio_latency_update_ready__signal = QtCore.pyqtSignal(str)
def __init__(self, shared_objects):
super(UbiquitiStatus, self).__init__()
# ########## Reference to class init variables ##########
self.shared_objects = shared_objects
self.left_screen = self.shared_objects["screens"]["left_screen"]
self.connection_quality_label = self.left_screen.connection_quality_label
self.successful_transmit_label = self.left_screen.successful_transmit_label
self.radio_rates_label = self.left_screen.radio_rates_label
self.radio_latency_label = self.left_screen.radio_latency_label
# ########## Get the settings instance ##########
self.settings = QtCore.QSettings()
# ########## Get the Pick And Plate instance of the logger ##########
self.logger = logging.getLogger("groundstation")
# ########## Thread Flags ##########
self.run_thread_flag = True
# ########## Class Variables ##########
self.wait_time = 1.0 / THREAD_HERTZ
self.ssh_client = None
def run(self):
try:
self.setup_and_connect_ssh_client()
except Exception:
return
while self.run_thread_flag:
start_time = time()
try:
self.get_and_show_ubiquiti_status()
except Exception, e:
print e
time_diff = time() - start_time
self.msleep(max(int((self.wait_time - time_diff) * 1000), 0))
def setup_and_connect_ssh_client(self):
self.ssh_client = paramiko.SSHClient()
self.ssh_client.set_missing_host_key_policy(paramiko.AutoAddPolicy())
self.ssh_client.connect(ACCESS_POINT_IP, username=ACCESS_POINT_USER, password=ACCESS_POINT_PASSWORD,
compress=True)
def get_and_show_ubiquiti_status(self):
ssh_stdin, ssh_stdout, ssh_stderr = self.ssh_client.exec_command(GENERAL_WIRELESS_INFO_COMMAND)
try:
output_json = json.loads(ssh_stdout.read())[0]
transmit_percent = output_json["ccq"]
quality = output_json["airmax"]["quality"]
# capacity = output_json["airmax"]["capacity"]
rx_rate = output_json["rx"]
tx_rate = output_json["tx"]
ground_tx_latency = output_json["tx_latency"]
rover_tx_latency = output_json["remote"]["tx_latency"]
except IndexError:
transmit_percent = 0
quality = 0
# capacity = output_json["airmax"]["capacity"]
rx_rate = 0
tx_rate = 0
ground_tx_latency = "----"
rover_tx_latency = "----"
self.connection_quality_update_ready__signal.emit("Connection Quality\n%s %%" % quality)
self.successful_transmission_update_ready__signal.emit("Successful Transmit\n%s %%" % transmit_percent)
self.radio_rates_update_ready__signal.emit("TX Rate: %s Mbps\nRX Rate: %s Mbps" % (tx_rate, rx_rate))
self.radio_latency_update_ready__signal.emit(
"TX Latency: %s ms\nRX Latency: %s ms" % (ground_tx_latency, rover_tx_latency))
def connect_signals_and_slots(self):
self.connection_quality_update_ready__signal.connect(self.connection_quality_label.setText)
self.successful_transmission_update_ready__signal.connect(self.successful_transmit_label.setText)
self.radio_rates_update_ready__signal.connect(self.radio_rates_label.setText)
self.radio_latency_update_ready__signal.connect(self.radio_latency_label.setText)
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
start_signal.connect(self.start)
signals_and_slots_signal.connect(self.connect_signals_and_slots)
kill_signal.connect(self.on_kill_threads_requested__slot)
def on_kill_threads_requested__slot(self):
self.run_thread_flag = False

View File

@@ -0,0 +1,391 @@
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore, QtWidgets
import logging
from time import time
import rospy
# Custom Imports
import RoverVideoReceiver
from rover_camera.msg import CameraControlMessage
#####################################
# Global Variables
#####################################
CAMERA_TOPIC_PATH = "/cameras/"
EXCLUDED_CAMERAS = ["zed"]
PRIMARY_LABEL_MAX = (640, 360)
SECONDARY_LABEL_MAX = (640, 360)
TERTIARY_LABEL_MAX = (640, 360)
LOW_RES = (256, 144)
GUI_SELECTION_CHANGE_TIMEOUT = 3 # Seconds
STYLESHEET_SELECTED = "border: 2px solid orange; background-color:black;"
STYLESHEET_UNSELECTED = "background-color:black;"
COLOR_GREEN = "background-color: darkgreen;"
COLOR_RED = "background-color: darkred;"
#####################################
# RoverVideoCoordinator Class Definition
#####################################
class RoverVideoCoordinator(QtCore.QThread):
pixmap_ready_signal = QtCore.pyqtSignal(str)
update_element_stylesheet__signal = QtCore.pyqtSignal()
pan_tilt_selection_changed__signal = QtCore.pyqtSignal(str)
low_res_button_text_update_ready__signal = QtCore.pyqtSignal(str)
low_res_button_stylesheet_update_ready__signal = QtCore.pyqtSignal(str)
def __init__(self, shared_objects):
super(RoverVideoCoordinator, self).__init__()
# ########## Reference to class init variables ##########
self.shared_objects = shared_objects
self.right_screen = self.shared_objects["screens"]["right_screen"]
self.primary_video_display_label = self.right_screen.primary_video_label # type:QtWidgets.QLabel
self.secondary_video_display_label = self.right_screen.secondary_video_label # type:QtWidgets.QLabel
self.tertiary_video_display_label = self.right_screen.tertiary_video_label # type:QtWidgets.QLabel
self.low_res_mode_button = self.right_screen.low_res_mode_button # type: QtWidgets.QLabel
self.index_to_label_element = {
0: self.primary_video_display_label,
1: self.secondary_video_display_label,
2: self.tertiary_video_display_label
}
# ########## Get the settings instance ##########
self.settings = QtCore.QSettings()
# ########## Get the Pick And Plate instance of the logger ##########
self.logger = logging.getLogger("groundstation")
# ########## Thread Flags ##########
self.run_thread_flag = True
self.setup_cameras_flag = True
# ########## Class Variables ##########
# Camera variables
self.camera_threads = {}
self.valid_cameras = []
self.disabled_cameras = []
reset_camera_message = CameraControlMessage()
reset_camera_message.enable_small_broadcast = True
# Reset default cameras
rospy.Publisher("/cameras/chassis/camera_control", CameraControlMessage, queue_size=1).publish(reset_camera_message)
rospy.Publisher("/cameras/undercarriage/camera_control", CameraControlMessage, queue_size=1).publish(reset_camera_message)
rospy.Publisher("/cameras/main_navigation/camera_control", CameraControlMessage, queue_size=1).publish(reset_camera_message)
rospy.Publisher("/cameras/end_effector/camera_control", CameraControlMessage, queue_size=1).publish(reset_camera_message)
self.msleep(3000)
# Setup cameras
self.main_nav_index = -1
self.chassis_index = -1
self.__get_cameras()
self.__setup_video_threads()
self.primary_label_current_setting = 0
self.secondary_label_current_setting = min(self.primary_label_current_setting + 1, len(self.valid_cameras))
self.tertiary_label_current_setting = min(self.secondary_label_current_setting + 1, len(self.valid_cameras))
self.index_to_label_current_setting = {
0: self.primary_label_current_setting,
1: self.secondary_label_current_setting,
2: self.tertiary_label_current_setting
}
self.current_label_for_joystick_adjust = 0
self.gui_selection_changed = True
self.last_gui_selection_changed_time = time()
self.set_max_resolutions_flag = True
self.first_image_received = False
self.in_low_res_mode = False
def run(self):
self.logger.debug("Starting Video Coordinator Thread")
self.__broadcast_current_pan_tilt_selection()
while self.run_thread_flag:
self.__set_max_resolutions()
self.__toggle_background_cameras_if_needed()
self.__update_gui_element_selection()
self.msleep(10)
self.__wait_for_camera_threads()
self.logger.debug("Stopping Video Coordinator Thread")
def __broadcast_current_pan_tilt_selection(self):
setting = None
if self.current_label_for_joystick_adjust == 0: # primary
setting = self.primary_label_current_setting
elif self.current_label_for_joystick_adjust == 1: # secondary
setting = self.secondary_label_current_setting
elif self.current_label_for_joystick_adjust == 2: # tertiary
setting = self.tertiary_label_current_setting
if setting == self.main_nav_index:
self.pan_tilt_selection_changed__signal.emit("tower_pan_tilt")
elif setting == self.chassis_index:
self.pan_tilt_selection_changed__signal.emit("chassis_pan_tilt")
else:
self.pan_tilt_selection_changed__signal.emit("no_pan_tilt")
def __set_max_resolutions(self):
if self.set_max_resolutions_flag:
if self.in_low_res_mode:
for camera in self.camera_threads:
self.camera_threads[camera].set_hard_max_resolution(LOW_RES)
else:
self.camera_threads[self.valid_cameras[self.primary_label_current_setting]].set_hard_max_resolution(PRIMARY_LABEL_MAX)
if self.secondary_label_current_setting != self.primary_label_current_setting:
self.camera_threads[self.valid_cameras[self.secondary_label_current_setting]].set_hard_max_resolution(SECONDARY_LABEL_MAX)
if self.tertiary_label_current_setting != self.primary_label_current_setting and self.tertiary_label_current_setting != self.secondary_label_current_setting:
self.camera_threads[self.valid_cameras[self.tertiary_label_current_setting]].set_hard_max_resolution(SECONDARY_LABEL_MAX)
self.set_max_resolutions_flag = False
def __toggle_background_cameras_if_needed(self):
enabled = list({self.primary_label_current_setting, self.secondary_label_current_setting,
self.tertiary_label_current_setting})
for camera_index, camera_name in enumerate(self.valid_cameras):
if camera_index not in enabled and camera_index not in self.disabled_cameras and self.camera_threads[camera_name].video_enabled:
self.camera_threads[camera_name].toggle_video_display()
elif camera_index in enabled and camera_index not in self.disabled_cameras and not self.camera_threads[camera_name].video_enabled:
self.camera_threads[camera_name].toggle_video_display()
def __update_gui_element_selection(self):
if (time() - self.last_gui_selection_changed_time) > GUI_SELECTION_CHANGE_TIMEOUT \
and self.gui_selection_changed:
elements_to_reset = range(len(self.index_to_label_element))
for index in elements_to_reset:
self.index_to_label_element[index].setStyleSheet(STYLESHEET_UNSELECTED)
self.gui_selection_changed = False
def __on_gui_element_stylesheet_update__slot(self):
elements_to_reset = range(len(self.index_to_label_element))
elements_to_reset.remove(self.current_label_for_joystick_adjust)
for index in elements_to_reset:
self.index_to_label_element[index].setStyleSheet(STYLESHEET_UNSELECTED)
self.index_to_label_element[self.current_label_for_joystick_adjust].setStyleSheet(STYLESHEET_SELECTED)
self.gui_selection_changed = True
self.last_gui_selection_changed_time = time()
def __get_cameras(self):
topics = rospy.get_published_topics(CAMERA_TOPIC_PATH)
names = []
for topics_group in topics:
main_topic = topics_group[0]
if "heartbeat" in main_topic:
continue
camera_name = main_topic.split("/")[2]
names.append(camera_name)
names = set(names)
for camera in EXCLUDED_CAMERAS:
if camera in names:
names.remove(camera)
self.valid_cameras = []
current_count = 0
if "main_navigation" in names:
self.valid_cameras.append("main_navigation")
self.main_nav_index = current_count
current_count += 1
if "chassis" in names:
self.valid_cameras.append("chassis")
self.chassis_index = current_count
if "undercarriage" in names:
self.valid_cameras.append("undercarriage")
if "end_effector" in names:
self.valid_cameras.append("end_effector")
def __setup_video_threads(self):
for camera in self.valid_cameras:
self.camera_threads[camera] = RoverVideoReceiver.RoverVideoReceiver(camera)
def __wait_for_camera_threads(self):
for camera in self.camera_threads:
self.camera_threads[camera].wait()
def connect_signals_and_slots(self):
for thread in self.camera_threads:
self.camera_threads[thread].image_ready_signal.connect(self.pixmap_ready__slot)
self.primary_video_display_label.mousePressEvent = self.__change_display_source_primary_mouse_press_event
self.secondary_video_display_label.mousePressEvent = self.__change_display_source_secondary_mouse_press_event
self.tertiary_video_display_label.mousePressEvent = self.__change_display_source_tertiary_mouse_press_event
self.shared_objects["threaded_classes"]["Joystick Sender"].change_gui_element_selection__signal.connect(
self.on_camera_gui_element_selection_changed)
self.shared_objects["threaded_classes"]["Joystick Sender"].change_camera_selection__signal.connect(
self.on_camera_selection_for_current_gui_element_changed)
self.shared_objects["threaded_classes"]["Joystick Sender"].toggle_selected_gui_camera__signal.connect(
self.on_gui_selected_camera_toggled)
self.low_res_mode_button.clicked.connect(self.on_low_res_button_clicked__slot)
self.low_res_button_text_update_ready__signal.connect(self.low_res_mode_button.setText)
self.low_res_button_stylesheet_update_ready__signal.connect(self.low_res_mode_button.setStyleSheet)
self.update_element_stylesheet__signal.connect(self.__on_gui_element_stylesheet_update__slot)
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
start_signal.connect(self.start)
signals_and_slots_signal.connect(self.connect_signals_and_slots)
kill_signal.connect(self.on_kill_threads_requested__slot)
for camera in self.camera_threads:
self.camera_threads[camera].setup_signals(start_signal, signals_and_slots_signal, kill_signal)
def __change_display_source_primary_mouse_press_event(self, event):
if event.button() == QtCore.Qt.LeftButton:
self.primary_label_current_setting = (self.primary_label_current_setting + 1) % len(self.valid_cameras)
self.set_max_resolutions_flag = True
elif event.button() == QtCore.Qt.RightButton:
if self.primary_label_current_setting in self.disabled_cameras:
self.disabled_cameras.remove(self.primary_label_current_setting)
else:
self.disabled_cameras.append(self.primary_label_current_setting)
self.camera_threads[self.valid_cameras[self.primary_label_current_setting]].toggle_video_display()
def __change_display_source_secondary_mouse_press_event(self, event):
if event.button() == QtCore.Qt.LeftButton:
self.secondary_label_current_setting = (self.secondary_label_current_setting + 1) % len(self.valid_cameras)
self.set_max_resolutions_flag = True
elif event.button() == QtCore.Qt.RightButton:
if self.secondary_label_current_setting in self.disabled_cameras:
self.disabled_cameras.remove(self.secondary_label_current_setting)
else:
self.disabled_cameras.append(self.secondary_label_current_setting)
self.camera_threads[self.valid_cameras[self.secondary_label_current_setting]].toggle_video_display()
def __change_display_source_tertiary_mouse_press_event(self, event):
if event.button() == QtCore.Qt.LeftButton:
self.tertiary_label_current_setting = (self.tertiary_label_current_setting + 1) % len(self.valid_cameras)
self.set_max_resolutions_flag = True
elif event.button() == QtCore.Qt.RightButton:
if self.tertiary_label_current_setting in self.disabled_cameras:
self.disabled_cameras.remove(self.tertiary_label_current_setting)
else:
self.disabled_cameras.append(self.tertiary_label_current_setting)
self.camera_threads[self.valid_cameras[self.tertiary_label_current_setting]].toggle_video_display()
def pixmap_ready__slot(self, camera):
if self.valid_cameras[self.primary_label_current_setting] == camera:
try:
self.primary_video_display_label.setPixmap(self.camera_threads[camera].pixmap_1280x720_image)
except:
pass
if self.valid_cameras[self.secondary_label_current_setting] == camera:
try:
self.secondary_video_display_label.setPixmap(self.camera_threads[camera].pixmap_640x360_image)
except:
pass
if self.valid_cameras[self.tertiary_label_current_setting] == camera:
try:
self.tertiary_video_display_label.setPixmap(self.camera_threads[camera].pixmap_640x360_image)
except:
pass
def on_camera_gui_element_selection_changed(self, direction):
new_selection = self.current_label_for_joystick_adjust - direction
if new_selection < 0:
self.current_label_for_joystick_adjust = len(self.index_to_label_element) - 1
elif new_selection == len(self.index_to_label_element):
self.current_label_for_joystick_adjust = 0
else:
self.current_label_for_joystick_adjust = new_selection
self.__broadcast_current_pan_tilt_selection()
self.update_element_stylesheet__signal.emit()
def on_camera_selection_for_current_gui_element_changed(self, direction):
if self.current_label_for_joystick_adjust == 0: # primary
self.primary_label_current_setting = (self.primary_label_current_setting + direction) % len(self.valid_cameras)
elif self.current_label_for_joystick_adjust == 1: # secondary
self.secondary_label_current_setting = (self.secondary_label_current_setting + direction) % len(self.valid_cameras)
elif self.current_label_for_joystick_adjust == 2: # tertiary
self.tertiary_label_current_setting = (self.tertiary_label_current_setting + direction) % len(self.valid_cameras)
self.__broadcast_current_pan_tilt_selection()
self.set_max_resolutions_flag = True
self.update_element_stylesheet__signal.emit()
def on_gui_selected_camera_toggled(self):
if self.current_label_for_joystick_adjust == 0: # primary
if self.primary_label_current_setting in self.disabled_cameras:
self.disabled_cameras.remove(self.primary_label_current_setting)
else:
self.disabled_cameras.append(self.primary_label_current_setting)
self.camera_threads[self.valid_cameras[self.primary_label_current_setting]].toggle_video_display()
elif self.current_label_for_joystick_adjust == 1: # secondary
if self.secondary_label_current_setting in self.disabled_cameras:
self.disabled_cameras.remove(self.secondary_label_current_setting)
else:
self.disabled_cameras.append(self.secondary_label_current_setting)
self.camera_threads[self.valid_cameras[self.secondary_label_current_setting]].toggle_video_display()
elif self.current_label_for_joystick_adjust == 2: # tertiary
if self.tertiary_label_current_setting in self.disabled_cameras:
self.disabled_cameras.remove(self.tertiary_label_current_setting)
else:
self.disabled_cameras.append(self.tertiary_label_current_setting)
self.camera_threads[self.valid_cameras[self.tertiary_label_current_setting]].toggle_video_display()
self.update_element_stylesheet__signal.emit()
def on_low_res_button_clicked__slot(self):
if self.low_res_mode_button.text() == "ENABLED":
self.in_low_res_mode = False
self.set_max_resolutions_flag = True
self.low_res_button_text_update_ready__signal.emit("DISABLED")
self.low_res_button_stylesheet_update_ready__signal.emit(COLOR_GREEN)
else:
self.in_low_res_mode = True
self.set_max_resolutions_flag = True
self.low_res_button_text_update_ready__signal.emit("ENABLED")
self.low_res_button_stylesheet_update_ready__signal.emit(COLOR_RED)
def on_kill_threads_requested__slot(self):
self.run_thread_flag = False

View File

@@ -0,0 +1,268 @@
#####################################
# Imports
#####################################
# Python native imports
from PyQt5 import QtCore, QtGui, QtWidgets
import logging
import cv2
import numpy as np
import qimage2ndarray
from time import time
import rospy
import dynamic_reconfigure.client
from cv_bridge import CvBridge
from sensor_msgs.msg import CompressedImage
# Custom Imports
from rover_camera.msg import CameraControlMessage
#####################################
# Global Variables
#####################################
CAMERA_TOPIC_PATH = "/cameras/"
QUALITY_MAX = 80
QUALITY_MIN = 15
FRAMERATE_AVERAGING_TIME = 10 # seconds
MIN_FRAMERATE_BEFORE_ADJUST = 23
MAX_FRAMERATE_BEFORE_ADJUST = 28
#####################################
# RoverVideoReceiver Class Definition
#####################################
class RoverVideoReceiver(QtCore.QThread):
image_ready_signal = QtCore.pyqtSignal(str)
RESOLUTION_OPTIONS = [(256, 144), (640, 360), (1280, 720)]
RESOLUTION_MAPPINGS = {
(1280, 720): None,
(640, 360): None,
(256, 144): None
}
def __init__(self, camera_name):
super(RoverVideoReceiver, self).__init__()
# ########## Reference to class init variables ##########
self.camera_name = camera_name
# ########## Get the settings instance ##########
self.settings = QtCore.QSettings()
# ########## Get the Pick And Plate instance of the logger ##########
self.logger = logging.getLogger("groundstation")
# ########## Thread Flags ##########
self.run_thread_flag = True
# ########## Class Variables ##########
self.camera_title_name = self.camera_name.replace("_", " ").title()
self.topic_base_path = CAMERA_TOPIC_PATH + self.camera_name
self.control_topic_path = self.topic_base_path + "/camera_control"
# Subscription variables
self.video_subscribers = []
# Publisher variables
self.camera_control_publisher = rospy.Publisher(self.control_topic_path, CameraControlMessage, queue_size=1)
# Set up resolution mappings
self.RESOLUTION_MAPPINGS[(1280, 720)] = CameraControlMessage()
self.RESOLUTION_MAPPINGS[(640, 360)] = CameraControlMessage()
self.RESOLUTION_MAPPINGS[(256, 144)] = CameraControlMessage()
self.RESOLUTION_MAPPINGS[(1280, 720)].enable_large_broadcast = True
self.RESOLUTION_MAPPINGS[(640, 360)].enable_medium_broadcast = True
self.RESOLUTION_MAPPINGS[(256, 144)].enable_small_broadcast = True
# Auto resolution adjustment variables
self.current_resolution_index = 1
self.last_resolution_index = self.current_resolution_index
self.max_resolution_index = len(self.RESOLUTION_OPTIONS)
self.frame_count = 0
self.last_framerate_time = time()
self.resolution_just_adjusted = False
# Image variables
self.raw_image = None
self.opencv_1280x720_image = None
self.opencv_640x360_image = None
self.pixmap_1280x720_image = None
self.pixmap_640x360_image = None
# Processing variables
self.bridge = CvBridge() # OpenCV ROS Video Data Processor
self.video_enabled = True
self.new_frame = False
# Text Drawing Variables
self.font = cv2.FONT_HERSHEY_TRIPLEX
self.font_thickness = 1
self.font_baseline = 0
self.camera_name_opencv_1280x720_image = None
self.camera_name_opencv_640x360_image = None
# Initial class setup to make text images and get camera resolutions
self.__create_camera_name_opencv_images()
# Attach subscribers now that everything is set up
self.video_subscribers.append(rospy.Subscriber(self.topic_base_path + "/image_1280x720/compressed", CompressedImage, self.__image_data_received_callback))
self.video_subscribers.append(rospy.Subscriber(self.topic_base_path + "/image_640x360/compressed", CompressedImage, self.__image_data_received_callback))
self.video_subscribers.append(rospy.Subscriber(self.topic_base_path + "/image_256x144/compressed", CompressedImage, self.__image_data_received_callback))
def run(self):
self.logger.debug("Starting \"%s\" Camera Thread" % self.camera_title_name)
self.__enable_camera_resolution(self.RESOLUTION_OPTIONS[self.current_resolution_index])
while self.run_thread_flag:
if self.video_enabled:
self.__show_video_enabled()
else:
self.__show_video_disabled()
self.msleep(10)
self.logger.debug("Stopping \"%s\" Camera Thread" % self.camera_title_name)
def __enable_camera_resolution(self, resolution):
self.camera_control_publisher.publish(self.RESOLUTION_MAPPINGS[resolution])
def __check_framerate_and_adjust_resolution(self):
time_diff = time() - self.last_framerate_time
if time_diff > FRAMERATE_AVERAGING_TIME:
current_fps = self.frame_count / time_diff
if current_fps >= MAX_FRAMERATE_BEFORE_ADJUST:
self.current_resolution_index = min(self.current_resolution_index + 1, self.max_resolution_index)
elif current_fps <= MIN_FRAMERATE_BEFORE_ADJUST:
self.current_resolution_index = max(self.current_resolution_index - 1, 0)
else:
self.current_resolution_index = min(self.current_resolution_index, self.max_resolution_index)
if self.last_resolution_index != self.current_resolution_index:
self.camera_control_publisher.publish(
self.RESOLUTION_MAPPINGS[self.RESOLUTION_OPTIONS[self.current_resolution_index]])
print "Setting %s to %s" % (self.camera_title_name, self.RESOLUTION_OPTIONS[self.current_resolution_index])
self.last_resolution_index = self.current_resolution_index
self.resolution_just_adjusted = True
# print "%s: %s FPS" % (self.camera_title_name, current_fps)
self.last_framerate_time = time()
self.frame_count = 0
def __show_video_enabled(self):
if self.new_frame:
self.__check_framerate_and_adjust_resolution()
try:
opencv_image = self.bridge.compressed_imgmsg_to_cv2(self.raw_image, "rgb8")
self.__create_final_pixmaps(opencv_image)
self.image_ready_signal.emit(self.camera_name)
except Exception, error:
print "Failed with error:" + str(error)
self.new_frame = False
def __show_video_disabled(self):
blank_frame = np.zeros((720, 1280, 3), np.uint8)
self.__create_final_pixmaps(blank_frame)
self.image_ready_signal.emit(self.camera_name)
def __create_final_pixmaps(self, opencv_image):
height, width, _ = opencv_image.shape
if width != 1280 and height != 720:
self.opencv_1280x720_image = cv2.resize(opencv_image, (1280, 720))
else:
self.opencv_1280x720_image = opencv_image
if width != 640 and height != 360:
self.opencv_640x360_image = cv2.resize(opencv_image, (640, 360))
else:
self.opencv_640x360_image = opencv_image
self.__apply_camera_name(self.opencv_1280x720_image, self.camera_name_opencv_1280x720_image)
self.__apply_camera_name(self.opencv_640x360_image, self.camera_name_opencv_640x360_image)
self.pixmap_1280x720_image = QtGui.QPixmap.fromImage(qimage2ndarray.array2qimage(
self.opencv_1280x720_image))
self.pixmap_640x360_image = QtGui.QPixmap.fromImage(qimage2ndarray.array2qimage(
self.opencv_640x360_image))
def __image_data_received_callback(self, raw_image):
self.raw_image = raw_image
self.frame_count += 1
self.new_frame = True
if self.resolution_just_adjusted:
self.frame_count = 0
self.last_framerate_time = time()
self.resolution_just_adjusted = False
def __create_camera_name_opencv_images(self):
camera_name_text_width, camera_name_text_height = \
cv2.getTextSize(self.camera_title_name, self.font, self.font_thickness, self.font_baseline)[0]
camera_name_width_buffered = camera_name_text_width + 10
camera_name_height_buffered = camera_name_text_height + 20
camera_name_opencv_image = np.zeros(
(camera_name_height_buffered, camera_name_width_buffered, 3), np.uint8)
cv2.putText(
camera_name_opencv_image,
self.camera_title_name,
((camera_name_width_buffered - camera_name_text_width) / 2, int((camera_name_height_buffered * 2) / 3)),
self.font,
1,
(255, 255, 255),
1,
cv2.LINE_AA)
self.camera_name_opencv_1280x720_image = \
cv2.resize(camera_name_opencv_image, (camera_name_width_buffered, camera_name_height_buffered))
self.camera_name_opencv_640x360_image = \
cv2.resize(camera_name_opencv_image, (camera_name_width_buffered / 2, camera_name_height_buffered / 2))
def set_hard_max_resolution(self, resolution):
self.max_resolution_index = self.RESOLUTION_OPTIONS.index(resolution)
def toggle_video_display(self):
if not self.video_enabled:
self.camera_control_publisher.publish(self.RESOLUTION_MAPPINGS[self.RESOLUTION_OPTIONS[self.current_resolution_index]])
self.video_enabled = True
self.new_frame = True
else:
self.camera_control_publisher.publish(CameraControlMessage())
self.video_enabled = False
def connect_signals_and_slots(self):
pass
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
start_signal.connect(self.start)
signals_and_slots_signal.connect(self.connect_signals_and_slots)
kill_signal.connect(self.on_kill_threads_requested__slot)
def on_kill_threads_requested__slot(self):
self.run_thread_flag = False
@staticmethod
def __apply_camera_name(opencv_image, font_opencv_image):
opencv_image[0:0 + font_opencv_image.shape[0], 0:0 + font_opencv_image.shape[1]] = \
font_opencv_image

View File

@@ -0,0 +1,14 @@
# Ground Station Software
This code is for the ground station side of the Mars Rover project.
## Requirements
* Python 2.X
* PyQt5
* ROS Kinetic
Python Libraries
* inputs
## How to Launch
Navigate to this directory on a linux system with the requirements listed above installed.
Run "python RoverGroundStation.py" or ./RoverGroundStation.py

Binary file not shown.

After

Width:  |  Height:  |  Size: 233 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 2.0 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 22 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 220 KiB

View File

@@ -0,0 +1,66 @@
# Note that the lat and lon positions below correspond to the center point of the maps you want to download
# Proper zoom level selection determines total viewable area
MAPPING_LOCATIONS = {
"Graf Hall": {
"latitude": 44.5675721667,
"longitude": -123.2750535,
"default_zoom": 18,
"valid_zoom_options": [16, 17, 18, 19, 20],
"pre_cache_map_zoom_levels": [18, 19, 20]
},
"Crystal Lake": {
"latitude": 44.547155,
"longitude": -123.251438,
"default_zoom": 18,
"valid_zoom_options": [16, 17, 18, 19, 20],
"pre_cache_map_zoom_levels": [18, 19, 20]
},
"Bend's \"The Pit\"": {
"latitude": 43.9941317,
"longitude": -121.4150066,
"default_zoom": 17,
"valid_zoom_options": [16, 17, 18, 19, 20],
"pre_cache_map_zoom_levels": [18, 19, 20]
},
"McMullen": {
"latitude": 51.470326,
"longitude": -112.773995,
"default_zoom": 17,
"valid_zoom_options": [16, 17, 18, 19, 20],
"pre_cache_map_zoom_levels": [18, 19, 20]
},
"Compound": {
"latitude": 51.470941,
"longitude": -112.752322,
"default_zoom": 17,
"valid_zoom_options": [16, 17, 18, 19, 20],
"pre_cache_map_zoom_levels": [18, 19, 20]
},
"1st Avenue": {
"latitude": 51.453744,
"longitude": -112.715879,
"default_zoom": 17,
"valid_zoom_options": [16, 17, 18, 19, 20],
"pre_cache_map_zoom_levels": [18, 19, 20]
},
"Rosedale": {
"latitude": 51.421368,
"longitude": -112.641666,
"default_zoom": 17,
"valid_zoom_options": [16, 17, 18, 19, 20],
"pre_cache_map_zoom_levels": [18, 19, 20]
},
}
LAST_SELECTION = "Graf Hall"
LAST_ZOOM_LEVEL = MAPPING_LOCATIONS[LAST_SELECTION]["default_zoom"]
# ##### This is the offset from magnetic north to true north
DECLINATION_OFFSET = 0 # We set this to 0 so we can use a phone to calibrate

View File

@@ -0,0 +1,207 @@
#####################################
# Imports
#####################################
# Python native imports
import sys
from PyQt5 import QtWidgets, QtCore, QtGui, uic
import signal
import rospy
import logging
import qdarkstyle
# Custom Imports
import Framework.StartupSystems.ROSMasterChecker as ROSMasterChecker
import Framework.LoggingSystems.Logger as Logger
import Framework.VideoSystems.RoverVideoCoordinator as RoverVideoCoordinator
import Framework.MapSystems.RoverMapCoordinator as RoverMapCoordinator
import Framework.ControlSystems.DriveAndCameraControlSender as JoystickControlSender
import Framework.ControlSystems.EffectorsAndArmControlSender as ControllerControlSender
import Framework.NavigationSystems.SpeedAndHeadingIndication as SpeedAndHeading
import Framework.NavigationSystems.WaypointsCoordinator as WaypointsCoordinator
import Framework.ArmSystems.ArmIndication as ArmIndication
import Framework.StatusSystems.StatusCore as StatusCore
import Framework.StatusSystems.UbiquitiStatusCore as UbiquitiStatusCore
import Framework.SettingsSystems.UbiquitiRadioSettings as UbiquitiRadioSettings
import Framework.MiscSystems.MiningCore as MiningCore
import Framework.MiscSystems.BashConsoleCore as BashConsoleCore
import Framework.MiscSystems.MiscArmCore as MiscArmCore
import Framework.MiscSystems.RDFCore as RDFCore
#####################################
# Global Variables
#####################################
UI_FILE_LEFT = "Resources/Ui/left_screen.ui"
UI_FILE_RIGHT = "Resources/Ui/right_screen.ui"
#####################################
# Class Organization
#####################################
# Class Name:
# "init"
# "run (if there)" - personal pref
# "private methods"
# "public methods, minus slots"
# "slot methods"
# "static methods"
# "run (if there)" - personal pref
#####################################
# ApplicationWindow Class Definition
#####################################
class ApplicationWindow(QtWidgets.QMainWindow):
exit_requested_signal = QtCore.pyqtSignal()
kill_threads_signal = QtCore.pyqtSignal()
def __init__(self, parent=None, ui_file_path=None):
super(ApplicationWindow, self).__init__(parent)
uic.loadUi(ui_file_path, self)
QtWidgets.QShortcut(QtGui.QKeySequence("Ctrl+Q"), self, self.exit_requested_signal.emit)
#####################################
# GroundStation Class Definition
#####################################
class GroundStation(QtCore.QObject):
LEFT_SCREEN_ID = 1
RIGHT_SCREEN_ID = 0
exit_requested_signal = QtCore.pyqtSignal()
start_threads_signal = QtCore.pyqtSignal()
connect_signals_and_slots_signal = QtCore.pyqtSignal()
kill_threads_signal = QtCore.pyqtSignal()
def __init__(self, parent=None,):
# noinspection PyArgumentList
super(GroundStation, self).__init__(parent)
# ##### Setup the Logger Immediately #####
self.logger_setup_class = Logger.Logger(console_output=True) # Doesn't need to be shared
# ########## Get the Pick And Plate instance of the logger ##########
self.logger = logging.getLogger("groundstation")
self.shared_objects = {
"screens": {},
"regular_classes": {},
"threaded_classes": {}
}
# ###### Instantiate Left And Right Screens ######
self.shared_objects["screens"]["left_screen"] = \
self.create_application_window(UI_FILE_LEFT, "Rover Ground Station Left Screen",
self.LEFT_SCREEN_ID) # type: ApplicationWindow
self.shared_objects["screens"]["right_screen"] = \
self.create_application_window(UI_FILE_RIGHT, "Rover Ground Station Right Screen",
self.RIGHT_SCREEN_ID) # type: ApplicationWindow
# ###### Initialize the Ground Station Node ######
rospy.init_node("ground_station")
# ##### Instantiate Regular Classes ######
self.__add_non_thread("Mining System", MiningCore.Mining(self.shared_objects))
self.__add_non_thread("Arm Indication", ArmIndication.ArmIndication(self.shared_objects))
# ##### Instantiate Threaded Classes ######
self.__add_thread("Video Coordinator", RoverVideoCoordinator.RoverVideoCoordinator(self.shared_objects))
self.__add_thread("Map Coordinator", RoverMapCoordinator.RoverMapCoordinator(self.shared_objects))
self.__add_thread("Joystick Sender", JoystickControlSender.DriveAndCameraControlSender(self.shared_objects))
self.__add_thread("Controller Sender", ControllerControlSender.EffectorsAndArmControlSender(self.shared_objects))
self.__add_thread("Speed and Heading", SpeedAndHeading.SpeedAndHeadingIndication(self.shared_objects))
self.__add_thread("Rover Status", StatusCore.SensorCore(self.shared_objects))
self.__add_thread("Ubiquiti Status", UbiquitiStatusCore.UbiquitiStatus(self.shared_objects))
self.__add_thread("Ubiquiti Radio Settings", UbiquitiRadioSettings.UbiquitiRadioSettings(self.shared_objects))
self.__add_thread("Waypoints Coordinator", WaypointsCoordinator.WaypointsCoordinator(self.shared_objects))
self.__add_thread("Bash Console", BashConsoleCore.BashConsole(self.shared_objects))
self.__add_thread("Misc Arm", MiscArmCore.MiscArm(self.shared_objects))
self.__add_thread("RDF", RDFCore.RDF(self.shared_objects))
self.connect_signals_and_slots_signal.emit()
self.__connect_signals_to_slots()
self.start_threads_signal.emit()
def ___ros_master_running(self):
checker = ROSMasterChecker.ROSMasterChecker()
if not checker.master_present(5):
self.logger.debug("ROS Master Not Found!!!! Exiting!!!")
QtGui.QGuiApplication.exit()
return False
return True
def __add_thread(self, thread_name, instance):
self.shared_objects["threaded_classes"][thread_name] = instance
instance.setup_signals(self.start_threads_signal, self.connect_signals_and_slots_signal,
self.kill_threads_signal)
def __add_non_thread(self, name, instance):
self.shared_objects["regular_classes"][name] = instance
def __connect_signals_to_slots(self):
self.shared_objects["screens"]["left_screen"].exit_requested_signal.connect(self.on_exit_requested__slot)
self.shared_objects["screens"]["right_screen"].exit_requested_signal.connect(self.on_exit_requested__slot)
def on_exit_requested__slot(self):
self.kill_threads_signal.emit()
# Wait for Threads
for thread in self.shared_objects["threaded_classes"]:
self.shared_objects["threaded_classes"][thread].wait()
QtGui.QGuiApplication.exit()
@staticmethod
def create_application_window(ui_file_path, title, display_screen):
system_desktop = QtWidgets.QDesktopWidget() # This gets us access to the desktop geometry
app_window = ApplicationWindow(parent=None, ui_file_path=ui_file_path) # Make a window in this application
app_window.setWindowTitle(title) # Sets the window title
app_window.setWindowFlags(app_window.windowFlags() | # Sets the windows flags to:
QtCore.Qt.FramelessWindowHint | # remove the border and frame on the application,
QtCore.Qt.WindowStaysOnTopHint | # and makes the window stay on top of all others
QtCore.Qt.X11BypassWindowManagerHint) # This is needed to show fullscreen in gnome
app_window.setGeometry(
system_desktop.screenGeometry(display_screen)) # Sets the window to be on the first screen
app_window.showFullScreen() # Shows the window in full screen mode
return app_window
#####################################
# Main Definition
#####################################
if __name__ == "__main__":
signal.signal(signal.SIGINT, signal.SIG_DFL) # This allows the keyboard interrupt kill to work properly
# ########## Start the QApplication Framework ##########
application = QtWidgets.QApplication(sys.argv) # Create the ase qt gui application
application.setStyleSheet(qdarkstyle.load_stylesheet_pyqt5())
# ########## Set Organization Details for QSettings ##########
QtCore.QCoreApplication.setOrganizationName("OSURC")
QtCore.QCoreApplication.setOrganizationDomain("http://osurobotics.club/")
QtCore.QCoreApplication.setApplicationName("groundstation")
# ########## Check ROS Master Status ##########
master_checker = ROSMasterChecker.ROSMasterChecker()
if not master_checker.master_present(5):
message_box = QtWidgets.QMessageBox()
message_box.setWindowTitle("Rover Ground Station")
message_box.setText("Connection to ROS Master Failed!!!\n" +
"Ensure ROS master is running or check for network issues.")
message_box.exec_()
exit()
# ########## Start Ground Station If Ready ##########
ground_station = GroundStation()
application.exec_() # Execute launching of the application

View File

@@ -0,0 +1,14 @@
cmake_minimum_required(VERSION 2.8.3)
project(mr1718-arm-urdf_export)
find_package(catkin REQUIRED)
catkin_package()
find_package(roslaunch)
foreach(dir config launch meshes urdf)
install(DIRECTORY ${dir}/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir})
endforeach(dir)

View File

@@ -0,0 +1 @@
controller_joint_names: ['shoulder', 'elbow', 'roll', 'wrist_base', 'wrist_pitch', 'wrist_roll', ]

View File

@@ -0,0 +1,26 @@
<launch>
<arg
name="model" />
<arg
name="gui"
default="False" />
<param
name="robot_description"
textfile="$(find mr1718-arm-urdf_export)/robots/mr1718-arm-urdf_export.urdf" />
<param
name="use_gui"
value="$(arg gui)" />
<node
name="joint_state_publisher"
pkg="joint_state_publisher"
type="joint_state_publisher" />
<node
name="robot_state_publisher"
pkg="robot_state_publisher"
type="state_publisher" />
<node
name="rviz"
pkg="rviz"
type="rviz"
args="-d $(find mr1718-arm-urdf_export)/urdf.rviz" />
</launch>

View File

@@ -0,0 +1,20 @@
<launch>
<include
file="$(find gazebo_ros)/launch/empty_world.launch" />
<node
name="tf_footprint_base"
pkg="tf"
type="static_transform_publisher"
args="0 0 0 0 0 0 base_link base_footprint 40" />
<node
name="spawn_model"
pkg="gazebo_ros"
type="spawn_model"
args="-file $(find mr1718-arm-urdf_export)/robots/mr1718-arm-urdf_export.urdf -urdf -model mr1718-arm-urdf_export"
output="screen" />
<node
name="fake_joint_calibration"
pkg="rostopic"
type="rostopic"
args="pub /calibrated std_msgs/Bool true" />
</launch>

View File

@@ -0,0 +1,21 @@
<package>
<name>mr1718-arm-urdf_export</name>
<version>1.0.0</version>
<description>
<p>URDF Description package for mr1718-arm-urdf_export</p>
<p>This package contains configuration data, 3D models and launch files
for mr1718-arm-urdf_export robot</p>
</description>
<author>me</author>
<maintainer email="me@email.com" />
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roslaunch</build_depend>
<run_depend>robot_state_publisher</run_depend>
<run_depend>rviz</run_depend>
<run_depend>joint_state_publisher</run_depend>
<run_depend>gazebo</run_depend>
<export>
<architecture_independent />
</export>
</package>

View File

@@ -0,0 +1,361 @@
<robot
name="mr1718-arm-urdf_export">
<link
name="base_link">
<inertial>
<origin
xyz="5.4755E-05 0.015543 0.0086991"
rpy="0 0 0" />
<mass
value="1.5519" />
<inertia
ixx="0.0045029"
ixy="-1.9571E-05"
ixz="1.1071E-05"
iyy="0.001083"
iyz="0.0012614"
izz="0.0038307" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/base_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/base_link.STL" />
</geometry>
</collision>
</link>
<link
name="shoulder_link">
<inertial>
<origin
xyz="-0.0076779 0.072439 -0.00025927"
rpy="0 0 0" />
<mass
value="1.2323" />
<inertia
ixx="0.00071817"
ixy="8.2844E-05"
ixz="4.663E-06"
iyy="0.0012756"
iyz="3.6626E-06"
izz="0.0019919" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/shoulder_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/shoulder_link.STL" />
</geometry>
</collision>
</link>
<joint
name="shoulder"
type="continuous">
<origin
xyz="0 0.0025248 0.091246"
rpy="1.5708 0 0" />
<parent
link="base_link" />
<child
link="shoulder_link" />
<axis
xyz="0 1 0" />
</joint>
<link
name="elbow_link">
<inertial>
<origin
xyz="0.052746 3.5254E-06 0.25018"
rpy="0 0 0" />
<mass
value="1.5164" />
<inertia
ixx="0.082218"
ixy="3.201E-09"
ixz="0.00060003"
iyy="0.082526"
iyz="-8.6916E-07"
izz="0.00030787" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/elbow_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/elbow_link.STL" />
</geometry>
</collision>
</link>
<joint
name="elbow"
type="continuous">
<origin
xyz="0.0335058907562339 0.0827436823988177 0"
rpy="0 0 0" />
<parent
link="shoulder_link" />
<child
link="elbow_link" />
<axis
xyz="1 0 0" />
</joint>
<link
name="roll_link">
<inertial>
<origin
xyz="-0.030978 -3.4831E-06 -0.0054534"
rpy="0 0 0" />
<mass
value="1.0721" />
<inertia
ixx="0.00049287"
ixy="3.3206E-08"
ixz="-3.6397E-06"
iyy="0.00051016"
iyz="-4.5289E-08"
izz="2.4367E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/roll_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/roll_link.STL" />
</geometry>
</collision>
</link>
<joint
name="roll"
type="continuous">
<origin
xyz="0 0 0.523621"
rpy="0 0 0" />
<parent
link="elbow_link" />
<child
link="roll_link" />
<axis
xyz="1 0 0" />
</joint>
<link
name="wrist_link">
<inertial>
<origin
xyz="-0.00095192 -4.7142E-05 0.25454"
rpy="0 0 0" />
<mass
value="0.60759" />
<inertia
ixx="0.0039577"
ixy="4.5025E-07"
ixz="5.7684E-05"
iyy="0.0042265"
iyz="1.2153E-06"
izz="0.00026882" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/wrist_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/wrist_link.STL" />
</geometry>
</collision>
</link>
<joint
name="wrist_base"
type="continuous">
<origin
xyz="-0.0345081407562338 0 0.048642197732"
rpy="0 0 0" />
<parent
link="roll_link" />
<child
link="wrist_link" />
<axis
xyz="0 0 1" />
</joint>
<link
name="wrist_pitch_link">
<inertial>
<origin
xyz="0.00095959 0.00027042 0.014957"
rpy="0 0 0" />
<mass
value="0.32143" />
<inertia
ixx="0.00011388"
ixy="-2.4963E-06"
ixz="2.1367E-06"
iyy="0.00018114"
iyz="1.3277E-06"
izz="6.9395E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/wrist_pitch_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/wrist_pitch_link.STL" />
</geometry>
</collision>
</link>
<joint
name="wrist_pitch"
type="continuous">
<origin
xyz="0 0 0.343027"
rpy="0 0 0" />
<parent
link="wrist_link" />
<child
link="wrist_pitch_link" />
<axis
xyz="1 0 0" />
</joint>
<link
name="wrist_roll_link">
<inertial>
<origin
xyz="-3.3391E-05 7.6495E-05 0.034573"
rpy="0 0 0" />
<mass
value="0.090203" />
<inertia
ixx="4.2212E-06"
ixy="9.452E-08"
ixz="1.6547E-08"
iyy="3.9599E-06"
iyz="-5.2152E-08"
izz="3.8149E-07" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/wrist_roll_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.75294 0.75294 0.75294 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://mr1718-arm-urdf_export/meshes/wrist_roll_link.STL" />
</geometry>
</collision>
</link>
<joint
name="wrist_roll"
type="continuous">
<origin
xyz="0 0 0.0227193855733502"
rpy="0 0 0" />
<parent
link="wrist_pitch_link" />
<child
link="wrist_roll_link" />
<axis
xyz="0 0 1" />
</joint>
</robot>

View File

@@ -0,0 +1,201 @@
cmake_minimum_required(VERSION 2.8)
project(nimbro_topic_transport)
find_package(catkin REQUIRED COMPONENTS
roscpp
topic_tools
rostest
message_generation
)
add_message_files(FILES
CompressedMsg.msg
ReceiverStats.msg
SenderStats.msg
TopicBandwidth.msg
)
generate_messages(DEPENDENCIES
std_msgs
)
catkin_package()
include_directories(${catkin_INCLUDE_DIRS})
# Some optional components of the NimbRo software framework
find_package(plot_msgs)
if(plot_msgs_FOUND)
include_directories(${plot_msgs_INCLUDE_DIRS})
add_definitions(-DWITH_PLOTTING=1)
endif()
find_package(config_server)
if(config_server_FOUND)
include_directories(${config_server_INCLUDE_DIRS})
add_definitions(-DWITH_CONFIG_SERVER=1)
endif()
find_package(catch_ros)
# If OpenFEC is available, we can enable FEC for the UDP sender
set(DEFAULT_OPENFEC_PATH /opt/openfec_v1.4.2)
set(OPENFEC_PATH "" CACHE PATH "Path to OpenFEC (optional)")
if(NOT OPENFEC_PATH AND IS_DIRECTORY ${DEFAULT_OPENFEC_PATH})
set(OPENFEC_PATH ${DEFAULT_OPENFEC_PATH})
endif()
if(OPENFEC_PATH)
include_directories(${OPENFEC_PATH}/src/lib_common)
set(OPENFEC_LIBRARY ${OPENFEC_PATH}/bin/Release/libopenfec.so)
add_definitions(-DWITH_OPENFEC=1)
message(STATUS "Found and using OpenFEC at: ${OPENFEC_PATH}")
else()
set(OPENFEC_LIBRARY "")
endif()
find_library(BZ2_LIBRARY bz2 REQUIRED)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -std=c++11")
add_executable(udp_sender
src/udp/topic_sender.cpp
src/udp/udp_sender.cpp
src/topic_info.cpp
)
add_dependencies(udp_sender
${PROJECT_NAME}_generate_messages_cpp
)
target_link_libraries(udp_sender
${catkin_LIBRARIES}
${BZ2_LIBRARY}
${OPENFEC_LIBRARY}
${config_server_LIBRARIES}
)
add_executable(udp_receiver
src/udp/udp_receiver.cpp
src/udp/topic_receiver.cpp
src/topic_info.cpp
)
add_dependencies(udp_receiver
${PROJECT_NAME}_generate_messages_cpp
)
target_link_libraries(udp_receiver
${catkin_LIBRARIES}
${BZ2_LIBRARY}
${OPENFEC_LIBRARY}
)
add_executable(tcp_sender
src/tcp/tcp_sender.cpp
src/topic_info.cpp
)
add_dependencies(tcp_sender
${PROJECT_NAME}_generate_messages_cpp
)
target_link_libraries(tcp_sender
${catkin_LIBRARIES}
${BZ2_LIBRARY}
${config_server_LIBRARIES}
)
add_executable(tcp_receiver
src/tcp/tcp_receiver.cpp
src/topic_info.cpp
)
add_dependencies(tcp_receiver
${PROJECT_NAME}_generate_messages_cpp
)
target_link_libraries(tcp_receiver
${catkin_LIBRARIES}
${BZ2_LIBRARY}
)
# Tools
add_executable(action_proxy
src/action_proxy.cpp
src/topic_info.cpp
)
target_link_libraries(action_proxy
${catkin_LIBRARIES}
)
# GUI
find_package(Qt4 REQUIRED)
include(${QT_USE_FILE})
qt4_wrap_cpp(MOC_SRCS
src/gui/topic_gui.h
src/gui/dot_widget.h
)
qt4_wrap_cpp(BAND_MOC_SRCS
src/gui/bandwidth_gui.h
src/gui/contrib/qcustomplot/qcustomplot.h
)
add_library(topic_gui
${MOC_SRCS}
src/gui/topic_gui.cpp
src/gui/dot_widget.cpp
)
add_library(bandwidth_gui
${BAND_MOC_SRCS}
src/gui/bandwidth_gui.cpp
src/gui/contrib/qcustomplot/qcustomplot.cpp
)
add_dependencies(topic_gui
${PROJECT_NAME}_generate_messages_cpp
)
target_link_libraries(topic_gui
${QT_LIBRARIES}
)
add_dependencies(bandwidth_gui
${PROJECT_NAME}_generate_messages_cpp
)
target_link_libraries(bandwidth_gui
${QT_LIBRARIES}
yaml-cpp
)
# Tests
if(catch_ros_FOUND)
include_directories(${catch_ros_INCLUDE_DIRS})
catch_add_rostest_node(test_comm
test/test_comm.cpp
)
target_link_libraries(test_comm
${catkin_LIBRARIES}
)
add_rostest(test/topic_transport.test ARGS protocol:=udp)
add_rostest(test/topic_transport.test ARGS protocol:=tcp)
if(OPENFEC_PATH)
add_rostest(test/topic_transport.test ARGS protocol:=udp fec:=true)
endif()
catch_add_rostest_node(test_bidirectional
test/test_bidirectional.cpp
)
target_link_libraries(test_bidirectional
${catkin_LIBRARIES}
)
add_rostest(test/bidirectional.test ARGS allow_bidirectional:=true)
add_rostest(test/bidirectional.test ARGS allow_bidirectional:=false)
endif()
#install
install(TARGETS udp_receiver tcp_receiver udp_sender tcp_sender
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION})

View File

@@ -0,0 +1,71 @@
nimbro_topic_transport
======================
This package includes nodes for transmitting ROS topic messages over a network
connection. For an overview over the available parameters, see
`doc/configuration.md`.
For a quick getting-started guide see `doc/getting_started.md`.
The remainder of this document introduces the features of the topic transport
and explains the choices you have in detail.
The fundamental choice you have is whether you want to use the TCP or the UDP
protocol.
UDP
---
The UDP protocol is the right choice for most ROS topics. It is especially
suited for lossy and/or delayed connections, where TCP has problems. Note
however, that with our UDP protocol there is no guarantee that a message
arrives.
Typical message types transmitted using the UDP protocol are camera images,
joystick commands, TF snapshots (see tf_throttle). In short, everything where
retransmitting missed packets does not make sense, because you have newer data
available already.
For example launch files, see the launch directory.
TCP
---
The TCP protocol is more useful for topics where you need a transmission
guarantee. For example, it makes sense to transmit 3D laser scans via this
method, because re-transmission of dropped packets is still faster than
waiting for the next scan.
For example launch files, see the launch directory.
Visualization & diagnosis
-------------------------
The nimbro_topic_transport package provides GUI plugins for the `rqt` GUI:
- "nimbro_network/Topic Transport" shows a dot graph of all network connections
- "nimbro_network/Topic Bandwidth" shows detailed bandwidth usage for a
single connection.
Note that it may be necessary to transmit the topics `/network/sender_stats` and
`/network/receiver_stats` over the network to get the full amount of
information.
Relay mode
----------
The UDP transport supports a special "relay" mode that was used in the DARPA
Robotics Challenge. Basically, it saturates a given target bitrate, repeating
messages if necessary. In the DRC, the high bandwidth link was switched on for
very short times (1 second). By saturating the available bandwidth, we made
sure that we got the maximum amount of data across in that window.
Forward error correction (FEC)
------------------------------
The UDP transport can do forward error correction if [OpenFEC][1] is available.
A short guide on how to install and configure the system is available
in `doc/FEC.md`.
[1]: http://openfec.org/

View File

@@ -0,0 +1,15 @@
<library path="lib/libbandwidth_gui">
<class name="BandwidthGui" type="nimbro_topic_transport::BandwidthGui" base_class_type="rqt_gui_cpp::Plugin">
<description>
Display bandwidth information for transferred topics
</description>
<qtgui>
<group>
<label>nimbro_network</label>
</group>
<label>Topic Bandwidth</label>
<statustip>Diagnostic information</statustip>
</qtgui>
</class>
</library>

View File

@@ -0,0 +1,18 @@
Forward Error Correction
========================
This is a short guide on how to get FEC running. If you want to use FEC,
you have to download [OpenFEC][OpenFEC] and compile it. Assuming you already
have compiled `nimbro_topic_transport` at least once, you can then inform
it about your OpenFEC installation:
```
cd my_catkin_workspace/build/nimbro_topic_transport
cmake -DOPENFEC_PATH=/path/to/openfec .
make
```
Afterwards, you can use the `fec` parameter on sender & receiver side as
described in `configuration.md`.
[OpenFEC]: http://openfec.org/

View File

@@ -0,0 +1,74 @@
Configuration
=============
`nimbro_topic_transport` is configured through ROS parameters.
Receiver parameters
-------------------
`tcp_receiver` and `udp_receiver` accept the following parameters:
Required:
- `port` (int): UDP/TCP port to bind to (required)
Optional:
- `drop_repeated_msgs` (bool): If a message with the same sequence number
arrives twice, drop it. Needed in conjunction with the relay mode.
(UDP only, default true)
- `fec` (bool): Enable Forward Error correction (UDP only, default false)
- `keep_compressed` (bool): Do not uncompress compressed topics, instead
publish them as the type `nimbro_topic_transport/CompressedMsg`
(default false)
- `label` (string): Display a label in the visualization GUIs
- `topic_prefix` (string): prepend topic_prefix before advertised topic names
- `warn_drop_incomplete` (bool): Display a warning every time an incomplete
packet is dropped (UDP only, default true)
Sender parameters
-----------------
`tcp_sender` and `udp_sender` accept the following parameters:
Required:
- `destination_addr` (string): Hostname or IP address of the destination
machine (required)
- `destination_port` (int): Port number to connect to (required)
- `source_port` (int): Source port to bind to. If not specified, the port is
chosen by the OS (TODO: true for udp_sender!)
- `topics` (list): List of topics to be transmitted (see below)
Optional:
- `fec` (float): If non-zero, this is the proportion of repair packets sent for
Forward Error Correction (0.5 -> Send 50% more data). This needs support for
FEC compiled in, see README.md (default 0.0)
- `label` (string): Display a label in the visualization GUIs
- `relay_mode` (bool): Enable relay mode, see README.md
(UDP only, default false)
- `relay_target_bitrate` (float): Target bitrate for relay mode (UDP only)
- `relay_control_rate` (float): Check if new packets can be sent in relay mode
at this rate (UDP only)
- `ignored_publishers` (list of string): Names of nodes whose messages should be
ignored if received by this sender. This should be used on both senders when
messages are to be sent to a topic both ways (always specify the name of the
receiver belonging to the other sender). See `launch/bidirectional_topics.launch`
for an example setup (TCP only)
Topic configuration
-------------------
Configuration of topics to be transmitted is done on the parameter server of
the sender's side. See the example launch files for the usual setup.
Here is a list of parameters that are available per topic. The only mandatory
parameter is `name`.
- `name`: Name of the topic to be sent over.
- `rate`: Rate limit on messages / sec (floating point). Messages over the
rate limit are silently dropped on the sender side. The default is 0.0
(no rate limit).
Note: Limiting only works well for lower rates (<20 Hz).
(UDP only)
- `resend`: If the sender does not get a message 1.0/`rate` after the last one,
it will re-send the last received one. (UDP only)
- `compress`: If true, compress the data on the wire with bz2.

View File

@@ -0,0 +1,26 @@
Getting started
===============
We assume that we have two machines, machineA and machineB. Both will be running
roscores, and we will transport some topics from machineA to machineB.
On machineA:
```bash
roslaunch nimbro_topic_transport udp_sender.launch target:=machineB
rostopic pub -r 1.0 /my_first_topic std_msgs/String "Hello World"
```
Instead of using the host name `machineB`, you can also use an IP address.
On machineB:
```bash
roslaunch nimbro_topic_transport udp_receiver.launch
rostopic echo /my_first_topic
```
You should see the `Hello World` messages arriving.
For customization, you should copy the launch files into your own package.

View File

@@ -0,0 +1,30 @@
<launch>
<arg name="target" default="localhost" />
<arg name="allow_bidirectional" default="true" />
<!-- The TCP sender node -->
<node name="tcp_sender_machine1" pkg="nimbro_topic_transport" type="tcp_sender" output="screen">
<!-- The destination host name or IP address -->
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17001" />
<!-- Load the list of topics from a YAML file -->
<rosparam command="load" file="$(find nimbro_topic_transport)/launch/topics_machine1.yaml" />
<!-- If bidirectional traffic over a topic is expected, fill this parameter.
See details in bidirectional_topics.launch -->
<rosparam param="ignored_publishers" if="$(arg allow_bidirectional)">["/tcp_receiver_machine1"]</rosparam>
<rosparam param="ignored_publishers" unless="$(arg allow_bidirectional)">[]</rosparam>
</node>
<node name="tcp_receiver_machine1" pkg="nimbro_topic_transport" type="tcp_receiver" output="screen">
<param name="port" value="17002" />
<!-- Remap topics so that sender & receiver do not clash if run on the
same machine. This is not necessary in a typical setup :-)
-->
<remap from="/recv/my_first_topic" to="/my_first_topic" />
</node>
</launch>

View File

@@ -0,0 +1,29 @@
<launch>
<arg name="target" default="localhost" />
<arg name="allow_bidirectional" default="true" />
<!-- The TCP sender node -->
<node name="tcp_sender_machine2" pkg="nimbro_topic_transport" type="tcp_sender" output="screen">
<!-- The destination host name or IP address -->
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17002" />
<!-- Load the list of topics from a YAML file -->
<rosparam command="load" file="$(find nimbro_topic_transport)/launch/topics_machine2.yaml" />
<!-- If bidirectional traffic over a topic is expected, fill this parameter.
See details in bidirectional_topics.launch -->
<rosparam param="ignored_publishers" if="$(arg allow_bidirectional)">["/tcp_receiver_machine2"]</rosparam>
<rosparam param="ignored_publishers" unless="$(arg allow_bidirectional)">[]</rosparam>
</node>
<node name="tcp_receiver_machine2" pkg="nimbro_topic_transport" type="tcp_receiver" output="screen">
<param name="port" value="17001" />
<!-- Remap topics so that sender & receiver do not clash if run on the
same machine. This is not necessary in a typical setup :-)
-->
<remap from="/my_first_topic" to="/recv/my_first_topic" />
</node>
</launch>

View File

@@ -0,0 +1,22 @@
<launch>
<arg name="allow_bidirectional" default="true" />
<!--
If you set up transports for a topic in both directions, don't forget to
provide the `ignored_publishers` parameter to both senders. Otherwise,
nimbro_network would enter an infinite republishing loop. You can test it
by playing with the `allow_bidirectional` argument and publishing to one
of the topics.
The `ignored_publishers` sender parameter is a list of node-names of
all receivers receiving any of the topics this publisher publishes.
-->
<include file="$(find nimbro_topic_transport)/launch/bidirectional_machine1.launch">
<arg name="allow_bidirectional" value="$(arg allow_bidirectional)" />
</include>
<include file="$(find nimbro_topic_transport)/launch/bidirectional_machine2.launch">
<arg name="allow_bidirectional" value="$(arg allow_bidirectional)" />
</include>
</launch>

View File

@@ -0,0 +1,4 @@
topics:
- name: "/cameras/camera_undercarriage/image_1280x720/compressed"
compress: false # enable bz2 compression
rate: 30.0 # rate limit at 1Hz

View File

@@ -0,0 +1,10 @@
topics:
- name: "/cameras/camera_chassis/image_640x360/compressed"
compress: false # enable bz2 compression
rate: 30.0 # rate limit at 1Hz
- name: "/cameras/camera_undercarriage/image_640x360/compressed"
compress: false # enable bz2 compression
rate: 30.0 # rate limit at 1Hz
- name: "/cameras/main_navigation/image_640x360/compressed"
compress: false # enable bz2 compression
rate: 30.0 # rate limit at 1Hz

View File

@@ -0,0 +1,4 @@
topics:
- name: "/cameras/main_navigation/image_1280x720/compressed"
compress: false # enable bz2 compression
rate: 30.0 # rate limit at 1Hz

View File

@@ -0,0 +1,11 @@
<launch>
<node name="tcp_receiver" pkg="nimbro_topic_transport" type="tcp_receiver" output="screen">
<param name="port" value="17001" />
<!-- Remap topics so that sender & receiver do not clash if run on the
same machine. This is not necessary in a typical setup :-)
-->
<remap from="/my_first_topic" to="/recv/my_first_topic" />
<remap from="/my_second_topic" to="/recv/my_second_topic" />
</node>
</launch>

View File

@@ -0,0 +1,14 @@
<launch>
<arg name="target" default="localhost" />
<!-- The UDP sender node -->
<node name="tcp_sender" pkg="nimbro_topic_transport" type="tcp_sender" output="screen">
<!-- The destination host name or IP address -->
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17001" />
<!-- Load the list of topics from a YAML file -->
<rosparam command="load" file="$(find nimbro_topic_transport)/launch/topics.yaml" />
</node>
</launch>

View File

@@ -0,0 +1,2 @@
topics:
- name: "/my_first_topic"

View File

@@ -0,0 +1,2 @@
topics:
- name: "/recv/my_first_topic"

View File

@@ -0,0 +1,37 @@
<launch>
<!--<node name="udp_receiver" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">-->
<!--<param name="port" value="17001" />-->
<!--</node>-->
<!--<node name="udp_receiver2" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">-->
<!--<param name="port" value="17002" />-->
<!--</node>-->
<!--<node name="udp_receiver3" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">-->
<!--<param name="port" value="17003" />-->
<!--</node>-->
<node name="udp_receiver4" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
<param name="port" value="17004" />
</node>
<node name="udp_receiver5" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
<param name="port" value="17005" />
</node>
<node name="udp_receiver6" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
<param name="port" value="17006" />
</node>
<node name="udp_receiver7" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
<param name="port" value="17007" />
</node>
<node name="udp_receiver8" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
<param name="port" value="17008" />
</node>
<node name="udp_receiver9" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
<param name="port" value="17009" />
</node>
</launch>

View File

@@ -0,0 +1,81 @@
<launch>
<arg name="target" default="192.168.1.15" />
<!-- The UDP sender node -->
<node name="udp_sender4" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
<!-- The destination host name or IP address -->
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17004" />
<!-- Load the list of topics from a YAML file -->
<rosparam param="topics">
[{name: "/cameras/camera_chassis/image_640x360/compressed", compress: false, rate: 30.0}]
</rosparam>
</node>
<!-- The UDP sender node -->
<node name="udp_sender5" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
<!-- The destination host name or IP address -->
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17005" />
<!-- Load the list of topics from a YAML file -->
<rosparam param="topics">
[{name: "/cameras/camera_undercarriage/image_640x360/compressed", compress: false, rate: 30.0}]
</rosparam>
</node>
<!-- The UDP sender node -->
<node name="udp_sender6" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
<!-- The destination host name or IP address -->
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17006" />
<!-- Load the list of topics from a YAML file -->
<rosparam param="topics">
[{name: "/cameras/main_navigation/image_640x360/compressed", compress: false, rate: 30.0}]
</rosparam>
</node>
<!-- The UDP sender node -->
<node name="udp_sender7" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
<!-- The destination host name or IP address -->
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17007" />
<!-- Load the list of topics from a YAML file -->
<rosparam param="topics">
[{name: "/cameras/camera_chassis/image_256x144/compressed", compress: false, rate: 30.0}]
</rosparam>
</node>
<!-- The UDP sender node -->
<node name="udp_sender8" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
<!-- The destination host name or IP address -->
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17008" />
<!-- Load the list of topics from a YAML file -->
<rosparam param="topics">
[{name: "/cameras/camera_undercarriage/image_256x144/compressed", compress: false, rate: 30.0}]
</rosparam>
</node>
<!-- The UDP sender node -->
<node name="udp_sender9" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
<!-- The destination host name or IP address -->
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17009" />
<!-- Load the list of topics from a YAML file -->
<rosparam param="topics">
[{name: "/cameras/main_navigation/image_256x144/compressed", compress: false, rate: 30.0}]
</rosparam>
</node>
</launch>

View File

@@ -0,0 +1,5 @@
<launch>
<node name="udp_receiver_drive" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
<param name="port" value="17020" />
</node>
</launch>

View File

@@ -0,0 +1,17 @@
<launch>
<arg name="target" default="192.168.1.10" />
<!-- The UDP sender node -->
<node name="udp_sender4" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
<!-- The destination host name or IP address -->
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17020" />
<!-- Load the list of topics from a YAML file -->
<rosparam param="topics">
[{name: "/command_control/groundstation_drive", compress: true, rate: 15.0}]
</rosparam>
</node>
</launch>

View File

@@ -0,0 +1,19 @@
<launch>
<!--
This launch file runs a udp_receiver node, which receives topics
over the network on port 17001 and publishes them on the local roscore.
See udp_sender.launch for the sender part.
-->
<node name="udp_receiver" pkg="nimbro_topic_transport" type="udp_receiver" output="screen">
<!-- The port to receive packets on -->
<param name="port" value="17001" />
<!-- Remap topics so that sender & receiver do not clash if run on the
same machine. This is not necessary in a typical setup :-)
-->
<remap from="/my_first_topic" to="/recv/my_first_topic" />
<remap from="/my_second_topic" to="/recv/my_second_topic" />
</node>
</launch>

View File

@@ -0,0 +1,26 @@
<launch>
<!--
This launch file runs a udp_sender node, which sends topics from the local
roscore over the network on port 17001.
By default, this launch file sends topics to your local machine for
testing purposes. If you want to send to another machine, use
roslaunch nimbro_topic_transport udp_sender.launch target:=other_host
where other_host can be a host name or IP address.
See udp_receiver.launch for the receiving part.
-->
<arg name="target" default="localhost" />
<!-- The UDP sender node -->
<node name="udp_sender" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
<!-- The destination host name or IP address -->
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17001" />
<!-- Load the list of topics from a YAML file -->
<rosparam command="load" file="$(find nimbro_topic_transport)/launch/topics.yaml" />
</node>
</launch>

View File

@@ -0,0 +1,8 @@
# Topic type (e.g. 'std_msgs/String')
string type
# Topic md5 sum
uint32[4] md5
uint8[] data

View File

@@ -0,0 +1,31 @@
Header header
# Node name
string node
# Protocol ("TCP" or "UDP")
string protocol
# Connection label
string label
# Local hostname
string host
# Remote hostname (if resolvable, otherwise IP)
string remote
# Port
uint16 local_port
# Port
uint16 remote_port
# is Forward Error Correction enabled?
bool fec
# Bandwidth in bit/s
float32 bandwidth
# Drop rate (estimated, percentage of missing packets in a fixed time interval)
float32 drop_rate

View File

@@ -0,0 +1,31 @@
Header header
# Node name
string node
# Protocol ("TCP" or "UDP")
string protocol
# Connection label
string label
# Local hostname
string host
# Destination address
string destination
# Destination port
uint16 destination_port
# Source port
uint16 source_port
# Is Forward Error Correction enabled?
bool fec
# Bandwidth in bit/s
float32 bandwidth
# Topic specific bandwidth
TopicBandwidth[] topics

View File

@@ -0,0 +1,4 @@
# Topic name
string name
# Bandwidth
float32 bandwidth

View File

@@ -0,0 +1,26 @@
<launch>
<!--
This launch file runs a udp_sender node, which sends topics from the local
roscore over the network on port 17001.
By default, this launch file sends topics to your local machine for
testing purposes. If you want to send to another machine, use
roslaunch nimbro_topic_transport udp_sender.launch target:=other_host
where other_host can be a host name or IP address.
See udp_receiver.launch for the receiving part.
-->
<arg name="target" default="192.168.1.10" />
<!-- The UDP sender node -->
<node name="udp_sender" pkg="nimbro_topic_transport" type="udp_sender" output="screen">
<!-- The destination host name or IP address -->
<param name="destination_addr" value="$(arg target)" />
<param name="destination_port" value="17001" />
<!-- Load the list of topics from a YAML file -->
<rosparam command="load" file="$(find nimbro_topic_transport)/launch/topics.yaml" />
</node>
</launch>

View File

@@ -0,0 +1,32 @@
<package format="2">
<name>nimbro_topic_transport</name>
<version>1.0.0</version>
<description>Contains nodes for TCP/UDP communication between ROS masters</description>
<maintainer email="max.schwarz@uni-bonn.de">Max Schwarz</maintainer>
<license>GPLv2</license>
<buildtool_depend>catkin</buildtool_depend>
<depend>roscpp</depend>
<depend>topic_tools</depend>
<build_depend>message_generation</build_depend>
<!-- This is not a hard dependency, the package compiles without plot_msgs. -->
<depend>plot_msgs</depend>
<!-- This is not a hard dependency, the package compiles without config_server. -->
<depend>config_server</depend>
<!-- This is not a hard dependency, the package compiles without catch_ros -->
<depend>catch_ros</depend>
<depend>rqt_gui</depend>
<export>
<rqt_gui plugin="${prefix}/rqt_plugin.xml" />
<rqt_gui plugin="${prefix}/bandwidth_plugin.xml" />
</export>
</package>

View File

@@ -0,0 +1,15 @@
<library path="lib/libtopic_gui">
<class name="topic_gui" type="nimbro_topic_transport::TopicGUI" base_class_type="rqt_gui_cpp::Plugin">
<description>
Display diagnostic information about the topic transport
</description>
<qtgui>
<group>
<label>nimbro_network</label>
</group>
<label>Topic Transport</label>
<statustip>Diagnostic information</statustip>
</qtgui>
</class>
</library>

View File

@@ -0,0 +1,138 @@
// Proxy node for action topics
// actionlib expects that all action topics are handled by a single node
// -- so republish / resubscribe them from here.
// Author: Max Schwarz <max.schwarz@uni-bonn.de>
#include <actionlib_msgs/GoalID.h>
#include <actionlib_msgs/GoalStatusArray.h>
#include <topic_tools/shape_shifter.h>
#include "topic_info.h"
ros::Subscriber m_sub_goal;
ros::Publisher m_pub_goal;
void handleGoal(const topic_tools::ShapeShifter::ConstPtr& goal)
{
m_pub_goal.publish(goal);
}
ros::Subscriber m_sub_cancel;
ros::Publisher m_pub_cancel;
void handleCancel(const actionlib_msgs::GoalID& id)
{
m_pub_cancel.publish(id);
}
ros::Subscriber m_sub_result;
ros::Publisher m_pub_result;
void handleResult(const topic_tools::ShapeShifter::ConstPtr& result)
{
m_pub_result.publish(result);
}
ros::Subscriber m_sub_status;
ros::Publisher m_pub_status;
void handleStatus(const actionlib_msgs::GoalStatusArray& status)
{
m_pub_status.publish(status);
}
ros::Subscriber m_sub_feedback;
ros::Publisher m_pub_feedback;
void handleFeedback(const topic_tools::ShapeShifter::ConstPtr& fb)
{
m_pub_feedback.publish(fb);
}
int main(int argc, char** argv)
{
ros::init(argc, argv, "action_proxy");
ros::NodeHandle nh("~");
std::string type;
if(!nh.getParam("type", type))
{
ROS_FATAL("need type parameter");
return 1;
}
std::string input;
if(!nh.getParam("input", input))
{
ROS_FATAL("need input parameter");
return 1;
}
std::string output;
if(!nh.getParam("output", output))
{
ROS_FATAL("need output parameter");
return 1;
}
{
ros::AdvertiseOptions ops;
ops.topic = input + "/goal";
ops.datatype = type + "ActionGoal";
ops.md5sum = nimbro_topic_transport::topic_info::getMd5Sum(ops.datatype);
m_pub_goal = nh.advertise(ops);
ros::SubscribeOptions subops;
subops.init<topic_tools::ShapeShifter>(output + "/goal", 10, boost::bind(&handleGoal, _1));
subops.datatype = type + "ActionGoal";
subops.md5sum = nimbro_topic_transport::topic_info::getMd5Sum(subops.datatype);
m_sub_goal = nh.subscribe(subops);
}
{
m_pub_cancel = nh.advertise<actionlib_msgs::GoalID>(input + "/cancel", 1);
m_sub_cancel = nh.subscribe(output + "/cancel", 10, &handleCancel);
}
{
ros::AdvertiseOptions ops;
ops.topic = output + "/result";
ops.datatype = type + "ActionResult";
ops.md5sum = nimbro_topic_transport::topic_info::getMd5Sum(ops.datatype);
m_pub_result = nh.advertise(ops);
ros::SubscribeOptions subops;
subops.init<topic_tools::ShapeShifter>(input + "/result", 10, boost::bind(&handleResult, _1));
subops.datatype = type + "ActionResult";
subops.md5sum = nimbro_topic_transport::topic_info::getMd5Sum(subops.datatype);
m_sub_result = nh.subscribe(subops);
}
{
ros::AdvertiseOptions ops;
ops.topic = output + "/feedback";
ops.datatype = type + "ActionFeedback";
ops.md5sum = nimbro_topic_transport::topic_info::getMd5Sum(ops.datatype);
m_pub_feedback = nh.advertise(ops);
ros::SubscribeOptions subops;
subops.init<topic_tools::ShapeShifter>(input + "/feedback", 10, boost::bind(&handleFeedback, _1));
subops.datatype = type + "ActionFeedback";
subops.md5sum = nimbro_topic_transport::topic_info::getMd5Sum(subops.datatype);
m_sub_feedback = nh.subscribe(subops);
}
{
m_pub_status = nh.advertise<actionlib_msgs::GoalStatusArray>(output + "/status", 10);
m_sub_status = nh.subscribe(input + "/status", 10, &handleStatus);
}
ros::spin();
return 0;
}

View File

@@ -0,0 +1,353 @@
// Bandwidth display for transferred topics
// Author: Sebastian Schüller
#include "bandwidth_gui.h"
#include "contrib/qcustomplot/qcustomplot.h"
#include <pluginlib/class_list_macros.h>
#include <ros/node_handle.h>
#include <yaml-cpp/yaml.h>
#include <algorithm>
#include <QLayout>
#include <QComboBox>
#include <QPushButton>
#include <QTextEdit>
#include <QMessageBox>
Q_DECLARE_METATYPE(nimbro_topic_transport::SenderStatsConstPtr)
static const int WINDOW_SIZE = 64;
static const int BRUSH_VALUE = 180;
static const int BRUSH_SATURATION = 150;
static const std::string DEFAULT_GROUPS =
"cameras: [\"/camera_center/h264\", \"/camera_left/h264\", \"/camera_right/h264\"]\n"
"hand_cameras: [\"/camera_left_hand/h264\", \"/camera_right_hand/h264\"]\n"
"network_stats: [\"/network/sender_stats\", \"/network/receiver_stats\"]\n";
inline double bpsToKbps(double bps)
{
return bps/1000.0;
}
inline double bpsToMbps(double bps)
{
return bpsToKbps(bps)/1000.0;
}
namespace nimbro_topic_transport
{
BandwidthGui::BandwidthGui()
: m_maxBandwidth(0)
, m_hue(175)
{}
BandwidthGui::~BandwidthGui()
{}
void BandwidthGui::initPlugin(qt_gui_cpp::PluginContext& ctx)
{
m_plot = new QCustomPlot();
m_plot->legend->setVisible(true);
m_plot->legend->setIconBorderPen(Qt::NoPen);
m_plot->yAxis->setLabel("Kb/s");
QWidget* wrapper = new QWidget();
m_connectionBox = new QComboBox(wrapper);
QPushButton* groupBtn = new QPushButton("Group Settings", wrapper);
QGridLayout* gl = new QGridLayout(wrapper);
gl->addWidget(m_plot, 0, 0, 1, 2);
gl->addWidget(m_connectionBox, 1, 0);
gl->addWidget(groupBtn, 1, 1);
wrapper->setLayout(gl);
wrapper->setWindowTitle("Bandwidth");
ctx.addWidget(wrapper);
connect(
m_plot, SIGNAL(legendClick(QCPLegend *, QCPAbstractLegendItem *, QMouseEvent *)),
this, SLOT(handleClickedLegend(QCPLegend*, QCPAbstractLegendItem*, QMouseEvent*))
);
connect(
m_connectionBox, SIGNAL(currentIndexChanged(int)),
this, SLOT(clearPlot())
);
connect(
groupBtn, SIGNAL(pressed()),
this, SLOT(updateGroupInfo())
);
qRegisterMetaType<nimbro_topic_transport::SenderStatsConstPtr>();
connect(
this, SIGNAL(senderStatsReceived(nimbro_topic_transport::SenderStatsConstPtr)),
this, SLOT(handleSenderStats(nimbro_topic_transport::SenderStatsConstPtr)),
Qt::QueuedConnection
);
m_sub_senderStats = getPrivateNodeHandle().subscribe(
"/network/sender_stats", 1, &BandwidthGui::senderStatsReceived, this
);
m_plot->xAxis->setTickLabelType(QCPAxis::ltDateTime);
m_plot->xAxis->setDateTimeFormat("hh:mm:ss");
m_plot->xAxis->setAutoTickStep(true);
m_plot->yAxis->setRangeLower(0);
QCPLayoutGrid* subLayout = new QCPLayoutGrid();
QCPLayoutElement* dummy = new QCPLayoutElement();
m_plot->plotLayout()->addElement(0, 1, subLayout);
subLayout->addElement(0, 0, m_plot->legend);
subLayout->addElement(1, 0, dummy);
subLayout->setRowStretchFactor(0, 0.01);
m_plot->plotLayout()->setColumnStretchFactor(1, 0.01);
connect(
m_plot->xAxis, SIGNAL(rangeChanged(QCPRange)),
m_plot->xAxis2, SLOT(setRange(QCPRange))
);
connect(
m_plot->yAxis, SIGNAL(rangeChanged(QCPRange)),
m_plot->yAxis2, SLOT(setRange(QCPRange))
);
connect(
&m_plotTimer, SIGNAL(timeout()),
this, SLOT(updatePlot())
);
m_plotTimer.start(0);
}
void BandwidthGui::shutdownPlugin()
{
m_sub_senderStats.shutdown();
}
void BandwidthGui::clearPlot()
{
m_maxBandwidth = 0;
m_bandwidths.clear();
m_plot->clearGraphs();
}
void BandwidthGui::handleSenderStats(const nimbro_topic_transport::SenderStatsConstPtr& msg)
{
// Update connection info
std::stringstream ss;
ss << "[" << msg->protocol << "] ";
ss << msg->host << ":" << msg->source_port << " -> ";
ss << msg->destination << ":" << msg->destination_port;
QString connection = QString::fromStdString(ss.str());
if(m_connectionBox->findText(connection) == -1)
m_connectionBox->addItem(connection);
if(connection != m_connectionBox->currentText())
return;
for(auto& gv : m_bandwidths)
gv.second.value = 0.0;
for(const auto& topic : msg->topics)
{
//Look up if topic is in group
std::string name = topic.name;
for(const auto& group : m_groupMap)
{
const auto& members = group.second;
if(std::find(members.begin(), members.end(), name) != members.end())
{
name = group.first;
break;
}
}
if(m_bandwidths.find(name) == m_bandwidths.end())
{
// Add and configure new graph to plot
auto graph = m_plot->addGraph();
graph->setName(QString::fromStdString(name));
graph->setPen(QPen(QColor::fromHsv(0,110,150)));
graph->setBrush(QBrush(QColor::fromHsv(m_hue, BRUSH_SATURATION, BRUSH_VALUE)));
m_hue = (m_hue + 137) % 360;
m_bandwidths[name].graph = graph;
m_bandwidths[name].last_timestamp = std::numeric_limits<double>::max();
}
m_bandwidths[name].value += bpsToKbps(topic.bandwidth);
m_bandwidths[name].timestamp = msg->header.stamp.toSec();
}
}
void BandwidthGui::updateGroupInfo()
{
QString temp;
GroupDialog dial; //ToDo find correct parent
dial.setText(m_grpYamlString);
int result = dial.exec();
if (result != QDialog::Accepted)
return;
temp = dial.text();
if (m_grpYamlString == temp)
return;
GroupMap groupMap;
if(!groupFromYaml(temp.toStdString(), &groupMap))
{
QMessageBox::warning(m_plot->parentWidget(), "Warning!", "Malformed YAML");
return;
}
m_grpYamlString = temp;
clearPlot();
m_groupMap = groupMap;
return;
}
bool BandwidthGui::groupFromYaml(const std::string& yaml, GroupMap* groupMap)
{
YAML::Node grpInfo = YAML::Load(yaml);
if (grpInfo.IsNull())
{
return true;
}
if (grpInfo.Type() != YAML::NodeType::Map)
{
return false;
}
for (const auto& pair : grpInfo)
{
if(pair.first.Type() != YAML::NodeType::Scalar)
{
return false;
}
std::string key = pair.first.as<std::string>();
for (const auto& element : pair.second)
{
if(element.Type() != YAML::NodeType::Scalar)
{
return false;
}
(*groupMap)[key].push_back(element.as<std::string>());
}
}
return true;
}
void BandwidthGui::updatePlot()
{
double plotValue = 0;
QCPGraph* prevGraph = nullptr;
for(auto& bw : m_bandwidths)
{
auto& gv = bw.second;
plotValue += gv.value;
if(prevGraph)
gv.graph->setChannelFillGraph(prevGraph);
prevGraph = gv.graph;
gv.graph->addData(gv.timestamp, plotValue);
m_maxBandwidth = std::max(m_maxBandwidth, plotValue);
m_plot->yAxis->setRangeUpper(m_maxBandwidth + (m_maxBandwidth/50.0));
gv.graph->removeDataBefore(5*WINDOW_SIZE);
gv.last_timestamp = gv.timestamp;
}
m_plot->xAxis->setRange(ros::Time::now().toSec() + 0.25, WINDOW_SIZE, Qt::AlignRight);
m_plot->replot();
}
void BandwidthGui::handleClickedLegend(QCPLegend *legend, QCPAbstractLegendItem *item, QMouseEvent *event)
{
QCPPlottableLegendItem* graphItem = dynamic_cast<QCPPlottableLegendItem*>(item);
if(!graphItem)
return;
auto color = graphItem->plottable()->brush().color();
auto hue = color.hue() + 180 % 360;
auto sat = color.saturation();
auto val = color.value();
if(sat == BRUSH_SATURATION)
{
sat = 255;
val = 255;
}
else
{
sat = BRUSH_SATURATION;
val = BRUSH_VALUE;
}
color.setHsv(hue, sat, val);
graphItem->plottable()->setBrush(QBrush(color));
}
void BandwidthGui::saveSettings(qt_gui_cpp::Settings& pluginSettings, qt_gui_cpp::Settings& instanceSettings) const
{
instanceSettings.setValue("connection", m_connectionBox->currentText());
instanceSettings.setValue("groups", m_grpYamlString);
}
void BandwidthGui::restoreSettings(const qt_gui_cpp::Settings& pluginSettings, const qt_gui_cpp::Settings& instanceSettings)
{
if(instanceSettings.contains("connection"))
m_connectionBox->addItem(instanceSettings.value("connection").toString());
if(instanceSettings.contains("groups"))
{
m_grpYamlString = instanceSettings.value("groups").toString();
GroupMap groupMap;
if(m_grpYamlString.isEmpty())
m_grpYamlString = QString::fromStdString(DEFAULT_GROUPS);
if(!groupFromYaml(m_grpYamlString.toStdString(), &groupMap))
{
m_grpYamlString = "";
return;
}
m_groupMap = groupMap;
}
}
////// Group Dialog
GroupDialog::GroupDialog()
: m_tEdit(new QTextEdit(this))
{
QPushButton* okBtn = new QPushButton("Accept", this);
QPushButton* cancelBtn = new QPushButton("Cancel", this);
QGridLayout* gl = new QGridLayout(this);
gl->addWidget(m_tEdit, 0, 0, 1, 2);
gl->addWidget(cancelBtn, 1, 0);
gl->addWidget(okBtn, 1, 1);
this->setLayout(gl);
connect(
okBtn, SIGNAL(pressed()),
this, SLOT(accept())
);
connect(
cancelBtn, SIGNAL(pressed()),
this, SLOT(reject())
);
}
void GroupDialog::setText(QString text)
{
m_tEdit->setPlainText(text);
}
QString GroupDialog::text()
{
return m_tEdit->toPlainText();
}
}
PLUGINLIB_EXPORT_CLASS(nimbro_topic_transport::BandwidthGui, rqt_gui_cpp::Plugin)

View File

@@ -0,0 +1,93 @@
// Bandwidth display for transferred topics
// Author: Sebastian Schüller
#ifndef BANDWIDTH_GUI
#define BANDWIDTH_GUI
#include <rqt_gui_cpp/plugin.h>
#include <ros/subscriber.h>
#include <nimbro_topic_transport/SenderStats.h>
#include <map>
#include <QTimer>
#include <QDialog>
class QCustomPlot;
class QCPGraph;
class QCPLegend;
class QCPAbstractLegendItem;
class QMouseEvent;
class QComboBox;
class QTextEdit;
typedef std::map<std::string, std::vector<std::string> > GroupMap;
namespace nimbro_topic_transport
{
class BandwidthGui : public rqt_gui_cpp::Plugin
{
Q_OBJECT
public:
BandwidthGui();
virtual ~BandwidthGui();
virtual void initPlugin(qt_gui_cpp::PluginContext & ) override;
virtual void shutdownPlugin() override;
virtual void saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const override;
virtual void restoreSettings(const qt_gui_cpp::Settings& pluginSettings, const qt_gui_cpp::Settings& instanceSettings) override;
Q_SIGNALS:
// Bounce SenderStats msg from ros thread to GUI thread
void senderStatsReceived(const nimbro_topic_transport::SenderStatsConstPtr& msg);
private Q_SLOTS:
void handleSenderStats(const nimbro_topic_transport::SenderStatsConstPtr& msg);
void updateGroupInfo();
void updatePlot();
void clearPlot();
void handleClickedLegend(QCPLegend *legend, QCPAbstractLegendItem *item, QMouseEvent *event);
private:
struct GraphValue
{
float value; // bandwidth value
double timestamp; // in seconds since epoch
double last_timestamp; // in seconds, timestamp of last point
QCPGraph* graph;
};
bool groupFromYaml(const std::string& yaml, GroupMap* map);
QCustomPlot* m_plot;
QComboBox* m_connectionBox;
QTimer m_plotTimer;
ros::Subscriber m_sub_senderStats;
std::map<std::string, GraphValue> m_bandwidths;
double m_maxBandwidth;
int m_hue;
std::vector<std::string> m_connections;
QString m_grpYamlString;
GroupMap m_groupMap;
};
// Text Dialog to change Group Settings
class GroupDialog : public QDialog
{
Q_OBJECT
public:
GroupDialog();
void setText(QString text);
QString text();
private:
QTextEdit* m_tEdit;
};
}
#endif

View File

@@ -0,0 +1,674 @@
GNU GENERAL PUBLIC LICENSE
Version 3, 29 June 2007
Copyright (C) 2007 Free Software Foundation, Inc. <http://fsf.org/>
Everyone is permitted to copy and distribute verbatim copies
of this license document, but changing it is not allowed.
Preamble
The GNU General Public License is a free, copyleft license for
software and other kinds of works.
The licenses for most software and other practical works are designed
to take away your freedom to share and change the works. By contrast,
the GNU General Public License is intended to guarantee your freedom to
share and change all versions of a program--to make sure it remains free
software for all its users. We, the Free Software Foundation, use the
GNU General Public License for most of our software; it applies also to
any other work released this way by its authors. You can apply it to
your programs, too.
When we speak of free software, we are referring to freedom, not
price. Our General Public Licenses are designed to make sure that you
have the freedom to distribute copies of free software (and charge for
them if you wish), that you receive source code or can get it if you
want it, that you can change the software or use pieces of it in new
free programs, and that you know you can do these things.
To protect your rights, we need to prevent others from denying you
these rights or asking you to surrender the rights. Therefore, you have
certain responsibilities if you distribute copies of the software, or if
you modify it: responsibilities to respect the freedom of others.
For example, if you distribute copies of such a program, whether
gratis or for a fee, you must pass on to the recipients the same
freedoms that you received. You must make sure that they, too, receive
or can get the source code. And you must show them these terms so they
know their rights.
Developers that use the GNU GPL protect your rights with two steps:
(1) assert copyright on the software, and (2) offer you this License
giving you legal permission to copy, distribute and/or modify it.
For the developers' and authors' protection, the GPL clearly explains
that there is no warranty for this free software. For both users' and
authors' sake, the GPL requires that modified versions be marked as
changed, so that their problems will not be attributed erroneously to
authors of previous versions.
Some devices are designed to deny users access to install or run
modified versions of the software inside them, although the manufacturer
can do so. This is fundamentally incompatible with the aim of
protecting users' freedom to change the software. The systematic
pattern of such abuse occurs in the area of products for individuals to
use, which is precisely where it is most unacceptable. Therefore, we
have designed this version of the GPL to prohibit the practice for those
products. If such problems arise substantially in other domains, we
stand ready to extend this provision to those domains in future versions
of the GPL, as needed to protect the freedom of users.
Finally, every program is threatened constantly by software patents.
States should not allow patents to restrict development and use of
software on general-purpose computers, but in those that do, we wish to
avoid the special danger that patents applied to a free program could
make it effectively proprietary. To prevent this, the GPL assures that
patents cannot be used to render the program non-free.
The precise terms and conditions for copying, distribution and
modification follow.
TERMS AND CONDITIONS
0. Definitions.
"This License" refers to version 3 of the GNU General Public License.
"Copyright" also means copyright-like laws that apply to other kinds of
works, such as semiconductor masks.
"The Program" refers to any copyrightable work licensed under this
License. Each licensee is addressed as "you". "Licensees" and
"recipients" may be individuals or organizations.
To "modify" a work means to copy from or adapt all or part of the work
in a fashion requiring copyright permission, other than the making of an
exact copy. The resulting work is called a "modified version" of the
earlier work or a work "based on" the earlier work.
A "covered work" means either the unmodified Program or a work based
on the Program.
To "propagate" a work means to do anything with it that, without
permission, would make you directly or secondarily liable for
infringement under applicable copyright law, except executing it on a
computer or modifying a private copy. Propagation includes copying,
distribution (with or without modification), making available to the
public, and in some countries other activities as well.
To "convey" a work means any kind of propagation that enables other
parties to make or receive copies. Mere interaction with a user through
a computer network, with no transfer of a copy, is not conveying.
An interactive user interface displays "Appropriate Legal Notices"
to the extent that it includes a convenient and prominently visible
feature that (1) displays an appropriate copyright notice, and (2)
tells the user that there is no warranty for the work (except to the
extent that warranties are provided), that licensees may convey the
work under this License, and how to view a copy of this License. If
the interface presents a list of user commands or options, such as a
menu, a prominent item in the list meets this criterion.
1. Source Code.
The "source code" for a work means the preferred form of the work
for making modifications to it. "Object code" means any non-source
form of a work.
A "Standard Interface" means an interface that either is an official
standard defined by a recognized standards body, or, in the case of
interfaces specified for a particular programming language, one that
is widely used among developers working in that language.
The "System Libraries" of an executable work include anything, other
than the work as a whole, that (a) is included in the normal form of
packaging a Major Component, but which is not part of that Major
Component, and (b) serves only to enable use of the work with that
Major Component, or to implement a Standard Interface for which an
implementation is available to the public in source code form. A
"Major Component", in this context, means a major essential component
(kernel, window system, and so on) of the specific operating system
(if any) on which the executable work runs, or a compiler used to
produce the work, or an object code interpreter used to run it.
The "Corresponding Source" for a work in object code form means all
the source code needed to generate, install, and (for an executable
work) run the object code and to modify the work, including scripts to
control those activities. However, it does not include the work's
System Libraries, or general-purpose tools or generally available free
programs which are used unmodified in performing those activities but
which are not part of the work. For example, Corresponding Source
includes interface definition files associated with source files for
the work, and the source code for shared libraries and dynamically
linked subprograms that the work is specifically designed to require,
such as by intimate data communication or control flow between those
subprograms and other parts of the work.
The Corresponding Source need not include anything that users
can regenerate automatically from other parts of the Corresponding
Source.
The Corresponding Source for a work in source code form is that
same work.
2. Basic Permissions.
All rights granted under this License are granted for the term of
copyright on the Program, and are irrevocable provided the stated
conditions are met. This License explicitly affirms your unlimited
permission to run the unmodified Program. The output from running a
covered work is covered by this License only if the output, given its
content, constitutes a covered work. This License acknowledges your
rights of fair use or other equivalent, as provided by copyright law.
You may make, run and propagate covered works that you do not
convey, without conditions so long as your license otherwise remains
in force. You may convey covered works to others for the sole purpose
of having them make modifications exclusively for you, or provide you
with facilities for running those works, provided that you comply with
the terms of this License in conveying all material for which you do
not control copyright. Those thus making or running the covered works
for you must do so exclusively on your behalf, under your direction
and control, on terms that prohibit them from making any copies of
your copyrighted material outside their relationship with you.
Conveying under any other circumstances is permitted solely under
the conditions stated below. Sublicensing is not allowed; section 10
makes it unnecessary.
3. Protecting Users' Legal Rights From Anti-Circumvention Law.
No covered work shall be deemed part of an effective technological
measure under any applicable law fulfilling obligations under article
11 of the WIPO copyright treaty adopted on 20 December 1996, or
similar laws prohibiting or restricting circumvention of such
measures.
When you convey a covered work, you waive any legal power to forbid
circumvention of technological measures to the extent such circumvention
is effected by exercising rights under this License with respect to
the covered work, and you disclaim any intention to limit operation or
modification of the work as a means of enforcing, against the work's
users, your or third parties' legal rights to forbid circumvention of
technological measures.
4. Conveying Verbatim Copies.
You may convey verbatim copies of the Program's source code as you
receive it, in any medium, provided that you conspicuously and
appropriately publish on each copy an appropriate copyright notice;
keep intact all notices stating that this License and any
non-permissive terms added in accord with section 7 apply to the code;
keep intact all notices of the absence of any warranty; and give all
recipients a copy of this License along with the Program.
You may charge any price or no price for each copy that you convey,
and you may offer support or warranty protection for a fee.
5. Conveying Modified Source Versions.
You may convey a work based on the Program, or the modifications to
produce it from the Program, in the form of source code under the
terms of section 4, provided that you also meet all of these conditions:
a) The work must carry prominent notices stating that you modified
it, and giving a relevant date.
b) The work must carry prominent notices stating that it is
released under this License and any conditions added under section
7. This requirement modifies the requirement in section 4 to
"keep intact all notices".
c) You must license the entire work, as a whole, under this
License to anyone who comes into possession of a copy. This
License will therefore apply, along with any applicable section 7
additional terms, to the whole of the work, and all its parts,
regardless of how they are packaged. This License gives no
permission to license the work in any other way, but it does not
invalidate such permission if you have separately received it.
d) If the work has interactive user interfaces, each must display
Appropriate Legal Notices; however, if the Program has interactive
interfaces that do not display Appropriate Legal Notices, your
work need not make them do so.
A compilation of a covered work with other separate and independent
works, which are not by their nature extensions of the covered work,
and which are not combined with it such as to form a larger program,
in or on a volume of a storage or distribution medium, is called an
"aggregate" if the compilation and its resulting copyright are not
used to limit the access or legal rights of the compilation's users
beyond what the individual works permit. Inclusion of a covered work
in an aggregate does not cause this License to apply to the other
parts of the aggregate.
6. Conveying Non-Source Forms.
You may convey a covered work in object code form under the terms
of sections 4 and 5, provided that you also convey the
machine-readable Corresponding Source under the terms of this License,
in one of these ways:
a) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by the
Corresponding Source fixed on a durable physical medium
customarily used for software interchange.
b) Convey the object code in, or embodied in, a physical product
(including a physical distribution medium), accompanied by a
written offer, valid for at least three years and valid for as
long as you offer spare parts or customer support for that product
model, to give anyone who possesses the object code either (1) a
copy of the Corresponding Source for all the software in the
product that is covered by this License, on a durable physical
medium customarily used for software interchange, for a price no
more than your reasonable cost of physically performing this
conveying of source, or (2) access to copy the
Corresponding Source from a network server at no charge.
c) Convey individual copies of the object code with a copy of the
written offer to provide the Corresponding Source. This
alternative is allowed only occasionally and noncommercially, and
only if you received the object code with such an offer, in accord
with subsection 6b.
d) Convey the object code by offering access from a designated
place (gratis or for a charge), and offer equivalent access to the
Corresponding Source in the same way through the same place at no
further charge. You need not require recipients to copy the
Corresponding Source along with the object code. If the place to
copy the object code is a network server, the Corresponding Source
may be on a different server (operated by you or a third party)
that supports equivalent copying facilities, provided you maintain
clear directions next to the object code saying where to find the
Corresponding Source. Regardless of what server hosts the
Corresponding Source, you remain obligated to ensure that it is
available for as long as needed to satisfy these requirements.
e) Convey the object code using peer-to-peer transmission, provided
you inform other peers where the object code and Corresponding
Source of the work are being offered to the general public at no
charge under subsection 6d.
A separable portion of the object code, whose source code is excluded
from the Corresponding Source as a System Library, need not be
included in conveying the object code work.
A "User Product" is either (1) a "consumer product", which means any
tangible personal property which is normally used for personal, family,
or household purposes, or (2) anything designed or sold for incorporation
into a dwelling. In determining whether a product is a consumer product,
doubtful cases shall be resolved in favor of coverage. For a particular
product received by a particular user, "normally used" refers to a
typical or common use of that class of product, regardless of the status
of the particular user or of the way in which the particular user
actually uses, or expects or is expected to use, the product. A product
is a consumer product regardless of whether the product has substantial
commercial, industrial or non-consumer uses, unless such uses represent
the only significant mode of use of the product.
"Installation Information" for a User Product means any methods,
procedures, authorization keys, or other information required to install
and execute modified versions of a covered work in that User Product from
a modified version of its Corresponding Source. The information must
suffice to ensure that the continued functioning of the modified object
code is in no case prevented or interfered with solely because
modification has been made.
If you convey an object code work under this section in, or with, or
specifically for use in, a User Product, and the conveying occurs as
part of a transaction in which the right of possession and use of the
User Product is transferred to the recipient in perpetuity or for a
fixed term (regardless of how the transaction is characterized), the
Corresponding Source conveyed under this section must be accompanied
by the Installation Information. But this requirement does not apply
if neither you nor any third party retains the ability to install
modified object code on the User Product (for example, the work has
been installed in ROM).
The requirement to provide Installation Information does not include a
requirement to continue to provide support service, warranty, or updates
for a work that has been modified or installed by the recipient, or for
the User Product in which it has been modified or installed. Access to a
network may be denied when the modification itself materially and
adversely affects the operation of the network or violates the rules and
protocols for communication across the network.
Corresponding Source conveyed, and Installation Information provided,
in accord with this section must be in a format that is publicly
documented (and with an implementation available to the public in
source code form), and must require no special password or key for
unpacking, reading or copying.
7. Additional Terms.
"Additional permissions" are terms that supplement the terms of this
License by making exceptions from one or more of its conditions.
Additional permissions that are applicable to the entire Program shall
be treated as though they were included in this License, to the extent
that they are valid under applicable law. If additional permissions
apply only to part of the Program, that part may be used separately
under those permissions, but the entire Program remains governed by
this License without regard to the additional permissions.
When you convey a copy of a covered work, you may at your option
remove any additional permissions from that copy, or from any part of
it. (Additional permissions may be written to require their own
removal in certain cases when you modify the work.) You may place
additional permissions on material, added by you to a covered work,
for which you have or can give appropriate copyright permission.
Notwithstanding any other provision of this License, for material you
add to a covered work, you may (if authorized by the copyright holders of
that material) supplement the terms of this License with terms:
a) Disclaiming warranty or limiting liability differently from the
terms of sections 15 and 16 of this License; or
b) Requiring preservation of specified reasonable legal notices or
author attributions in that material or in the Appropriate Legal
Notices displayed by works containing it; or
c) Prohibiting misrepresentation of the origin of that material, or
requiring that modified versions of such material be marked in
reasonable ways as different from the original version; or
d) Limiting the use for publicity purposes of names of licensors or
authors of the material; or
e) Declining to grant rights under trademark law for use of some
trade names, trademarks, or service marks; or
f) Requiring indemnification of licensors and authors of that
material by anyone who conveys the material (or modified versions of
it) with contractual assumptions of liability to the recipient, for
any liability that these contractual assumptions directly impose on
those licensors and authors.
All other non-permissive additional terms are considered "further
restrictions" within the meaning of section 10. If the Program as you
received it, or any part of it, contains a notice stating that it is
governed by this License along with a term that is a further
restriction, you may remove that term. If a license document contains
a further restriction but permits relicensing or conveying under this
License, you may add to a covered work material governed by the terms
of that license document, provided that the further restriction does
not survive such relicensing or conveying.
If you add terms to a covered work in accord with this section, you
must place, in the relevant source files, a statement of the
additional terms that apply to those files, or a notice indicating
where to find the applicable terms.
Additional terms, permissive or non-permissive, may be stated in the
form of a separately written license, or stated as exceptions;
the above requirements apply either way.
8. Termination.
You may not propagate or modify a covered work except as expressly
provided under this License. Any attempt otherwise to propagate or
modify it is void, and will automatically terminate your rights under
this License (including any patent licenses granted under the third
paragraph of section 11).
However, if you cease all violation of this License, then your
license from a particular copyright holder is reinstated (a)
provisionally, unless and until the copyright holder explicitly and
finally terminates your license, and (b) permanently, if the copyright
holder fails to notify you of the violation by some reasonable means
prior to 60 days after the cessation.
Moreover, your license from a particular copyright holder is
reinstated permanently if the copyright holder notifies you of the
violation by some reasonable means, this is the first time you have
received notice of violation of this License (for any work) from that
copyright holder, and you cure the violation prior to 30 days after
your receipt of the notice.
Termination of your rights under this section does not terminate the
licenses of parties who have received copies or rights from you under
this License. If your rights have been terminated and not permanently
reinstated, you do not qualify to receive new licenses for the same
material under section 10.
9. Acceptance Not Required for Having Copies.
You are not required to accept this License in order to receive or
run a copy of the Program. Ancillary propagation of a covered work
occurring solely as a consequence of using peer-to-peer transmission
to receive a copy likewise does not require acceptance. However,
nothing other than this License grants you permission to propagate or
modify any covered work. These actions infringe copyright if you do
not accept this License. Therefore, by modifying or propagating a
covered work, you indicate your acceptance of this License to do so.
10. Automatic Licensing of Downstream Recipients.
Each time you convey a covered work, the recipient automatically
receives a license from the original licensors, to run, modify and
propagate that work, subject to this License. You are not responsible
for enforcing compliance by third parties with this License.
An "entity transaction" is a transaction transferring control of an
organization, or substantially all assets of one, or subdividing an
organization, or merging organizations. If propagation of a covered
work results from an entity transaction, each party to that
transaction who receives a copy of the work also receives whatever
licenses to the work the party's predecessor in interest had or could
give under the previous paragraph, plus a right to possession of the
Corresponding Source of the work from the predecessor in interest, if
the predecessor has it or can get it with reasonable efforts.
You may not impose any further restrictions on the exercise of the
rights granted or affirmed under this License. For example, you may
not impose a license fee, royalty, or other charge for exercise of
rights granted under this License, and you may not initiate litigation
(including a cross-claim or counterclaim in a lawsuit) alleging that
any patent claim is infringed by making, using, selling, offering for
sale, or importing the Program or any portion of it.
11. Patents.
A "contributor" is a copyright holder who authorizes use under this
License of the Program or a work on which the Program is based. The
work thus licensed is called the contributor's "contributor version".
A contributor's "essential patent claims" are all patent claims
owned or controlled by the contributor, whether already acquired or
hereafter acquired, that would be infringed by some manner, permitted
by this License, of making, using, or selling its contributor version,
but do not include claims that would be infringed only as a
consequence of further modification of the contributor version. For
purposes of this definition, "control" includes the right to grant
patent sublicenses in a manner consistent with the requirements of
this License.
Each contributor grants you a non-exclusive, worldwide, royalty-free
patent license under the contributor's essential patent claims, to
make, use, sell, offer for sale, import and otherwise run, modify and
propagate the contents of its contributor version.
In the following three paragraphs, a "patent license" is any express
agreement or commitment, however denominated, not to enforce a patent
(such as an express permission to practice a patent or covenant not to
sue for patent infringement). To "grant" such a patent license to a
party means to make such an agreement or commitment not to enforce a
patent against the party.
If you convey a covered work, knowingly relying on a patent license,
and the Corresponding Source of the work is not available for anyone
to copy, free of charge and under the terms of this License, through a
publicly available network server or other readily accessible means,
then you must either (1) cause the Corresponding Source to be so
available, or (2) arrange to deprive yourself of the benefit of the
patent license for this particular work, or (3) arrange, in a manner
consistent with the requirements of this License, to extend the patent
license to downstream recipients. "Knowingly relying" means you have
actual knowledge that, but for the patent license, your conveying the
covered work in a country, or your recipient's use of the covered work
in a country, would infringe one or more identifiable patents in that
country that you have reason to believe are valid.
If, pursuant to or in connection with a single transaction or
arrangement, you convey, or propagate by procuring conveyance of, a
covered work, and grant a patent license to some of the parties
receiving the covered work authorizing them to use, propagate, modify
or convey a specific copy of the covered work, then the patent license
you grant is automatically extended to all recipients of the covered
work and works based on it.
A patent license is "discriminatory" if it does not include within
the scope of its coverage, prohibits the exercise of, or is
conditioned on the non-exercise of one or more of the rights that are
specifically granted under this License. You may not convey a covered
work if you are a party to an arrangement with a third party that is
in the business of distributing software, under which you make payment
to the third party based on the extent of your activity of conveying
the work, and under which the third party grants, to any of the
parties who would receive the covered work from you, a discriminatory
patent license (a) in connection with copies of the covered work
conveyed by you (or copies made from those copies), or (b) primarily
for and in connection with specific products or compilations that
contain the covered work, unless you entered into that arrangement,
or that patent license was granted, prior to 28 March 2007.
Nothing in this License shall be construed as excluding or limiting
any implied license or other defenses to infringement that may
otherwise be available to you under applicable patent law.
12. No Surrender of Others' Freedom.
If conditions are imposed on you (whether by court order, agreement or
otherwise) that contradict the conditions of this License, they do not
excuse you from the conditions of this License. If you cannot convey a
covered work so as to satisfy simultaneously your obligations under this
License and any other pertinent obligations, then as a consequence you may
not convey it at all. For example, if you agree to terms that obligate you
to collect a royalty for further conveying from those to whom you convey
the Program, the only way you could satisfy both those terms and this
License would be to refrain entirely from conveying the Program.
13. Use with the GNU Affero General Public License.
Notwithstanding any other provision of this License, you have
permission to link or combine any covered work with a work licensed
under version 3 of the GNU Affero General Public License into a single
combined work, and to convey the resulting work. The terms of this
License will continue to apply to the part which is the covered work,
but the special requirements of the GNU Affero General Public License,
section 13, concerning interaction through a network will apply to the
combination as such.
14. Revised Versions of this License.
The Free Software Foundation may publish revised and/or new versions of
the GNU General Public License from time to time. Such new versions will
be similar in spirit to the present version, but may differ in detail to
address new problems or concerns.
Each version is given a distinguishing version number. If the
Program specifies that a certain numbered version of the GNU General
Public License "or any later version" applies to it, you have the
option of following the terms and conditions either of that numbered
version or of any later version published by the Free Software
Foundation. If the Program does not specify a version number of the
GNU General Public License, you may choose any version ever published
by the Free Software Foundation.
If the Program specifies that a proxy can decide which future
versions of the GNU General Public License can be used, that proxy's
public statement of acceptance of a version permanently authorizes you
to choose that version for the Program.
Later license versions may give you additional or different
permissions. However, no additional obligations are imposed on any
author or copyright holder as a result of your choosing to follow a
later version.
15. Disclaimer of Warranty.
THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY
APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT
HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY
OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO,
THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM
IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF
ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
16. Limitation of Liability.
IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS
THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY
GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE
USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF
DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD
PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),
EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF
SUCH DAMAGES.
17. Interpretation of Sections 15 and 16.
If the disclaimer of warranty and limitation of liability provided
above cannot be given local legal effect according to their terms,
reviewing courts shall apply local law that most closely approximates
an absolute waiver of all civil liability in connection with the
Program, unless a warranty or assumption of liability accompanies a
copy of the Program in return for a fee.
END OF TERMS AND CONDITIONS
How to Apply These Terms to Your New Programs
If you develop a new program, and you want it to be of the greatest
possible use to the public, the best way to achieve this is to make it
free software which everyone can redistribute and change under these terms.
To do so, attach the following notices to the program. It is safest
to attach them to the start of each source file to most effectively
state the exclusion of warranty; and each file should have at least
the "copyright" line and a pointer to where the full notice is found.
<one line to give the program's name and a brief idea of what it does.>
Copyright (C) <year> <name of author>
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
Also add information on how to contact you by electronic and paper mail.
If the program does terminal interaction, make it output a short
notice like this when it starts in an interactive mode:
<program> Copyright (C) <year> <name of author>
This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'.
This is free software, and you are welcome to redistribute it
under certain conditions; type `show c' for details.
The hypothetical commands `show w' and `show c' should show the appropriate
parts of the General Public License. Of course, your program's commands
might be different; for a GUI interface, you would use an "about box".
You should also get your employer (if you work as a programmer) or school,
if any, to sign a "copyright disclaimer" for the program, if necessary.
For more information on this, and how to apply and follow the GNU GPL, see
<http://www.gnu.org/licenses/>.
The GNU General Public License does not permit incorporating your program
into proprietary programs. If your program is a subroutine library, you
may consider it more useful to permit linking proprietary applications with
the library. If this is what you want to do, use the GNU Lesser General
Public License instead of this License. But first, please read
<http://www.gnu.org/philosophy/why-not-lgpl.html>.

View File

@@ -0,0 +1,416 @@
#### Version 1.3.1 released on 25.04.15 ####
Bugfixes:
- Fixed bug that prevented automatic axis rescaling when some graphs/curves had only NaN data points
- Improved QCPItemBracket selection boundaries, especially bsCurly and bsCalligraphic
- Fixed bug of axis rect and colorscale background shifted downward by one logical pixel (visible in scaled png and pdf export)
- Replot upon mouse release is now only performed if a selection change has actually happened (improves responsivity on particularly complex plots)
- Fixed bug that allowed scatter-only graphs to be selected by clicking the non-existent line between scatters
- Fixed crash when trying to select a scatter-only QCPGraph whose only points in the visible key range are at identical key coordinates and vertically off-screen, with adaptive sampling enabled
- Fixed pdf export of QCPColorMap with enabled interpolation (didn't appear interpolated in pdf)
- Reduced QCPColorMap jitter of internal cell boundaries for small sized maps when viewed with high zoom, by applying oversampling factors dependant on map size
- Fixed bug of QCPColorMap::fill() not causing the buffered internal image map to be updated, and thus the change didn't become visible immediately
- Axis labels with size set in pixels (setPixelSize) instead of points now correctly calculate the exponent's font size if beautifully typeset powers are enabled
- Fixed QCPColorMap appearing at the wrong position for logarithmic axes and color map spanning larger ranges
Other:
- Pdf export used to embed entire QCPColorMaps, potentially leading to large files. Now only the visible portion of the map is embedded in the pdf
- Many documentation fixes and extensions, style modernization
- Reduced documentation file size (and thus full package size) by automatically reducing image palettes during package build
- Fixed MSVC warning message (at warning level 4) due to temporary QLists in some foreach statements
#### Version 1.3.0 released on 27.12.14 ####
Added features:
- New plottable class QCPFinancial allows display of candlestick/ohlc data
- New class QCPBarsGroup allows horizontal grouping of multiple QCPBars plottables
- Added QCPBars feature allowing non-zero base values (see property QCPBars::setBaseValue)
- Added QCPBars width type, for more flexible bar widths (see property QCPBars::setWidthType)
- New QCPCurve optimization algorithm, fixes bug which caused line flicker at deep zoom into curve segment
- Item positions can now have different position types and anchors for their x and y coordinates (QCPItemPosition::setTypeX/Y, setParentAnchorX/Y)
- QCPGraph and QCPCurve can now display gaps in their lines, when inserting quiet NaNs as values (std::numeric_limits<double>::quiet_NaN())
- QCPAxis now supports placing the tick labels inside the axis rect, for particularly space saving plots (QCPAxis::setTickLabelSide)
Added features after beta:
- Made code compatible with QT_NO_CAST_FROM_ASCII, QT_NO_CAST_TO_ASCII
- Added compatibility with QT_NO_KEYWORDS after sending code files through a simple reg-ex script
- Added possibility to inject own QCPAxis(-subclasses) via second, optional QCPAxisRect::addAxis parameter
- Added parameter to QCPItemPixmap::setScaled to specify transformation mode
Bugfixes:
- Fixed bug in QCPCurve rendering of very zoomed-in curves (via new optimization algorithm)
- Fixed conflict with MSVC-specific keyword "interface" in text-document-integration example
- Fixed QCPScatterStyle bug ignoring the specified pen in the custom scatter shape constructor
- Fixed bug (possible crash) during QCustomPlot teardown, when a QCPLegend that has no parent layout (i.e. was removed from layout manually) gets deleted
Bugfixes after beta:
- Fixed bug of QCPColorMap/QCPColorGradient colors being off by one color sampling step (only noticeable in special cases)
- Fixed bug of QCPGraph adaptive sampling on vertical key axis, causing staggered look
- Fixed low (float) precision in QCPCurve optimization algorithm, by not using QVector2D anymore
Other:
- Qt 5.3 and Qt 5.4 compatibility
#### Version 1.2.1 released on 07.04.14 ####
Bugfixes:
- Fixed regression which garbled date-time tick labels on axes, if setTickLabelType is ltDateTime and setNumberFormat contains the "b" option
#### Version 1.2.0 released on 14.03.14 ####
Added features:
- Adaptive Sampling for QCPGraph greatly improves performance for high data densities (see QCPGraph::setAdaptiveSampling)
- QCPColorMap plottable with QCPColorScale layout element allows plotting of 2D color maps
- QCustomPlot::savePdf now has additional optional parameters pdfCreator and pdfTitle to set according PDF metadata fields
- QCustomPlot::replot now allows specifying whether the widget update is immediate (repaint) or queued (update)
- QCPRange operators +, -, *, / with double operand for range shifting and scaling, and ==, != for range comparison
- Layers now have a visibility property (QCPLayer::setVisible)
- static functions QCPAxis::opposite and QCPAxis::orientation now offer more convenience when handling axis types
- added notification signals for selectability change (selectableChanged) on all objects that have a selected/selectable property
- added notification signal for QCPAxis scaleType property
- added notification signal QCPLayerable::layerChanged
Bugfixes:
- Fixed assert halt, when QCPAxis auto tick labels not disabled but nevertheless a custom non-number tick label ending in "e" given
- Fixed painting glitches when QCustomPlot resized inside a QMdiArea or under certain conditions inside a QLayout
- If changing QCPAxis::scaleType and thus causing range sanitizing and a range modification, rangeChanged wouldn't be emitted
- Fixed documentation bug that caused indentation to be lost in code examples
Bugfixes after beta:
- Fixed bug that caused crash if clicked-on legend item is removed in mousePressEvent.
- On some systems, font size defaults to -1, which used to cause a debug output in QCPAxisPainterPrivate::TickLabelDataQCP. Now it's checked before setting values based on the default font size.
- When using multiple axes on one side, setting one to invisible didn't properly compress the freed space.
- Fixed bug that allowed selection of plottables when clicking in the bottom or top margin of a QCPAxisRect (outside the inner rect)
Other:
- In method QCPAbstractPlottable::getKeyRange/getValueRange, renamed parameter "validRange" to "foundRange", to better reflect its meaning (and contrast it from QCPRange::validRange)
- QCPAxis low-level axis painting methods exported to QCPAxisPainterPrivate
#### Version 1.1.1 released on 09.12.13 ####
Bugfixes:
- Fixed bug causing legends blocking input events from reaching underlying axis rect even if legend is invisible
- Added missing Q_PROPERTY for QCPAxis::setDateTimeSpec
- Fixed behaviour of QCPAxisRect::setupFullAxesBox (now transfers more properties from bottom/left to top/right axes and sets visibility of bottom/left axes to true)
- Made sure PDF export doesn't default to grayscale output on some systems
Other:
- Plotting hint QCP::phForceRepaint is now enabled on all systems (and not only on windows) by default
- Documentation improvements
#### Version 1.1.0 released on 04.11.13 ####
Added features:
- Added QCPRange::expand and QCPRange::expanded
- Added QCPAxis::rescale to rescale axis to all associated plottables
- Added QCPAxis::setDateTimeSpec/dateTimeSpec to allow axis labels either in UTC or local time
- QCPAxis now additionally emits a rangeChanged signal overload that provides the old range as second parameter
Bugfixes:
- Fixed QCustomPlot::rescaleAxes not rescaling properly if first plottable has an empty range
- QCPGraph::rescaleAxes/rescaleKeyAxis/rescaleValueAxis are no longer virtual (never were in base class, was a mistake)
- Fixed bugs in QCPAxis::items and QCPAxisRect::items not properly returning associated items and potentially stalling
Other:
- Internal change from QWeakPointer to QPointer, thus got rid of deprecated Qt functionality
- Qt5.1 and Qt5.2 (beta1) compatibility
- Release packages now extract to single subdirectory and don't place multiple files in current working directory
#### Version 1.0.1 released on 05.09.13 ####
Bugfixes:
- using define flag QCUSTOMPLOT_CHECK_DATA caused debug output when data was correct, instead of invalid (fixed QCP::isInvalidData)
- documentation images are now properly shown when viewed with Qt Assistant
- fixed various documentation mistakes
Other:
- Adapted documentation style sheet to better match Qt5 documentation
#### Version 1.0.0 released on 01.08.13 ####
Quick Summary:
- Layout system for multiple axis rects in one plot
- Multiple axes per side
- Qt5 compatibility
- More flexible and consistent scatter configuration with QCPScatterStyle
- Various interface cleanups/refactoring
- Pixmap-cached axis labels for improved replot performance
Changes that break backward compatibility:
- QCustomPlot::axisRect() changed meaning due to the extensive changes to how axes and axis rects are handled
it now returns a pointer to a QCPAxisRect and takes an integer index as parameter.
- QCPAxis constructor changed to now take QCPAxisRect* as parent
- setAutoMargin, setMarginLeft/Right/Top/Bottom removed due to the axis rect changes (see QCPAxisRect::setMargins/setAutoMargins)
- setAxisRect removed due to the axis rect changes
- setAxisBackground(-Scaled/-ScaledMode) now moved to QCPAxisRect as setBackground(-Scaled/ScaledMode) (access via QCustomPlot::axisRects())
- QCPLegend now is a QCPLayoutElement
- QCPAbstractPlottable::drawLegendIcon parameter "rect" changed from QRect to QRectF
- QCPAbstractLegendItem::draw second parameter removed (position/size now handled via QCPLayoutElement base class)
- removed QCPLegend::setMargin/setMarginLeft/Right/Top/Bottom (now inherits the capability from QCPLayoutElement::setMargins)
- removed QCPLegend::setMinimumSize (now inherits the capability from QCPLayoutElement::setMinimumSize)
- removed enum QCPLegend::PositionStyle, QCPLegend::positionStyle/setPositionStyle/position/setPosition (replaced by capabilities of QCPLayoutInset)
- QCPLegend transformed to work with new layout system (almost everything changed)
- removed entire title interface: QCustomPlot::setTitle/setTitleFont/setTitleColor/setTitleSelected/setTitleSelectedFont/setTitleSelectedColor and
the QCustomPlot::iSelectTitle interaction flag (all functionality is now given by the layout element "QCPPlotTitle" which can be added to the plot layout)
- selectTest functions now take two additional parameters: bool onlySelectable and QVariant *details=0
- selectTest functions now ignores visibility of objects and (if parameter onlySelectable is true) does not anymore ignore selectability of the object
- moved QCustomPlot::Interaction/Interactions to QCP namespace as QCP::Interaction/Interactions
- moved QCustomPlot::setupFullAxesBox() to QCPAxisRect::setupFullAxesBox. Now also accepts parameter to decide whether to connect opposite axis ranges
- moved range dragging/zooming interface from QCustomPlot to QCPAxisRect (setRangeDrag, setRangeZoom, setRangeDragAxes, setRangeZoomAxes,...)
- rangeDrag/Zoom is now set to Qt::Horizontal|Qt::Vertical instead of 0 by default, on the other hand, iRangeDrag/Zoom is unset in interactions by
default (this makes enabling dragging/zooming easier by just adding the interaction flags)
- QCPScatterStyle takes over everything related to handling scatters in all plottables
- removed setScatterPen/Size on QCPGraph and QCPCurve, removed setOutlierPen/Size on QCPStatisticalBox (now handled via QCPScatterStyle)
- modified setScatterStyle on QCPGraph and QCPCurve, and setOutlierStyle on QCPStatisticalBox, to take QCPScatterStyle
- axis grid and subgrid are now reachable via the QCPGrid *QCPAxis::grid() method. (e.g. instead of xAxis->setGrid(true), write xAxis->grid()->setVisible(true))
Added features:
- Axis tick labels are now pixmap-cached, thus increasing replot performance (in usual setups by about 24%). See plotting hint phCacheLabels which is set by default
- Advanced layout system, including the classes QCPLayoutElement, QCPLayout, QCPLayoutGrid, QCPLayoutInset, QCPAxisRect
- QCustomPlot::axisRects() returns all the axis rects in the QCustomPlot.
- QCustomPlot::plotLayout() returns the top level layout (initially a QCPLayoutGrid with one QCPAxisRect inside)
- QCPAxis now may have an offset to the axis rect (setOffset)
- Multiple axes per QCPAxisRect side are now supported (see QCPAxisRect::addAxis)
- QCustomPlot::toPixmap renders the plot into a pixmap and returns it
- When setting tick label rotation to +90 or -90 degrees on a vertical axis, the labels are now centered vertically on the tick height
(This allows space saving vertical tick labels by having the text direction parallel to the axis)
- Substantially increased replot performance when using very large manual tick vectors (> 10000 ticks) via QCPAxis::setTickVector
- QCPAxis and QCPAxisRect now allow easy access to all plottables(), graphs() and items() that are associated with them
- Added QCustomPlot::hasItem method for consistency with plottable interface, hasPlottable
- Added QCPAxisRect::setMinimumMargins as replacement for hardcoded minimum axis margin (15 px) when auto margin is enabled
- Added Flags type QCPAxis::AxisTypes (from QCPAxis::AxisType), used in QCPAxisRect interface
- Automatic margin calculation can now be enabled/disabled on a per-side basis, see QCPAxisRect::setAutoMargins
- QCPAxisRect margins of multiple axis rects can be coupled via QCPMarginGroup
- Added new default layers "background" and "legend" (QCPAxisRect draws its background on the "background" layer, QCPLegend is on the "legend" layer by default)
- Custom scatter style via QCP::ssCustom and respective setCustomScatter functions that take a QPainterPath
- Filled scatters via QCPScatterStyle::setBrush
Added features after beta:
- Added QCustomPlot::toPainter method, to allow rendering with existing painter
- QCPItemEllipse now provides a center anchor
Bugfixes:
- Fixed compile error on ARM
- Wrong legend icons were displayed if using pixmaps for scatters that are smaller than the legend icon rect
- Fixed clipping inaccuracy for rotated tick labels (were hidden too early, because the non-rotated bounding box was used)
- Fixed bug that caused wrong clipping of axis ticks and subticks when the ticks were given manually by QCPAxis::setTickVector
- Fixed Qt5 crash when dragging graph out of view (iterator out of bounds in QCPGraph::getVisibleDataBounds)
- Fixed QCPItemText not scaling properly when using scaled raster export
Bugfixes after beta:
- Fixed bug that clipped the rightmost pixel column of tick labels when caching activated (only visible on windows for superscript exponents)
- Restored compatibility to Qt4.6
- Restored support for -no-RTTI compilation
- Empty manual tick labels are handled more gracefully (no QPainter qDebug messages anymore)
- Fixed type ambiguity in QCPLineEnding::draw causing compile error on ARM
- Fixed bug of grid layouts not propagating the minimum size from their child elements to the parent layout correctly
- Fixed bug of child elements (e.g. axis rects) of inset layouts not properly receiving mouse events
Other:
- Opened up non-amalgamated project structure to public via git repository
#### Version released on 09.06.12 ####
Quick Summary:
- Items (arrows, text,...)
- Layers (easier control over rendering order)
- New antialiasing system (Each objects controls own antialiasing with setAntialiased)
- Performance Improvements
- improved pixel-precise drawing
- easier shared library creation/usage
Changes that (might) break backward compatibility:
- enum QCPGraph::ScatterSymbol was moved to QCP namespace (now QCP::ScatterSymbol).
This replace should fix your code: "QCPGraph::ss" -> "QCP::ss"
- enum QCustomPlot::AntialiasedElement and flag QCustomPlot::AntialiasedElements was moved to QCP namespace
This replace should fix your code: "QCustomPlot::ae" -> "QCP::ae"
- the meaning of QCustomPlot::setAntialiasedElements has changed slightly: It is now an override to force elements to be antialiased. If you want to force
elements to not be drawn antialiased, use the new setNotAntialiasedElements. If an element is mentioned in neither of those functions, it now controls
its antialiasing itself via its "setAntialiased" function(s). (e.g. QCPAxis::setAntialiased(bool), QCPAbstractPlottable::setAntialiased(bool),
QCPAbstractPlottable::setAntialiasedScatters(bool), etc.)
- QCPAxis::setTickVector and QCPAxis::setTickVectorLabels no longer take a pointer but a const reference of the respective QVector as parameter.
(handing over a pointer didn't give any noticeable performance benefits but was inconsistent with the rest of the interface)
- Equally QCPAxis::tickVector and QCPAxis::tickVectorLabels don't return by pointer but by value now
- QCustomPlot::savePngScaled was removed, its purpose is now included as optional parameter "scale" of savePng.
- If you have derived from QCPAbstractPlottable: all selectTest functions now consistently take the argument "const QPointF &pos" which is the test point in pixel coordinates.
(the argument there was "double key, double value" in plot coordinates, before).
- QCPAbstractPlottable, QCPAxis and QCPLegend now inherit from QCPLayerable
- If you have derived from QCPAbstractPlottable: the draw method signature has changed from "draw (..) const" to "draw (..)", i.e. the method
is not const anymore. This allows the draw function of your plottable to perform buffering/caching operations, if necessary.
Added features:
- Item system: QCPAbstractItem, QCPItemAnchor, QCPItemPosition, QCPLineEnding. Allows placing of lines, arrows, text, pixmaps etc.
- New Items: QCPItemStraightLine, QCPItemLine, QCPItemCurve, QCPItemEllipse, QCPItemRect, QCPItemPixmap, QCPItemText, QCPItemBracket, QCPItemTracer
- QCustomPlot::addItem/itemCount/item/removeItem/selectedItems
- signals QCustomPlot::itemClicked/itemDoubleClicked
- the QCustomPlot interactions property now includes iSelectItems (for selection of QCPAbstractItem)
- QCPLineEnding. Represents the different styles a line/curve can end (e.g. different arrows, circle, square, bar, etc.), see e.g. QCPItemCurve::setHead
- Layer system: QCPLayerable, QCPLayer. Allows more sophisticated control over drawing order and a kind of grouping.
- QCPAbstractPlottable, QCPAbstractItem, QCPAxis, QCPGrid, QCPLegend are layerables and derive from QCPLayerable
- QCustomPlot::addLayer/moveLayer/removeLayer/setCurrentLayer/layer/currentLayer/layerCount
- Initially there are three layers: "grid", "main", and "axes". The "main" layer is initially empty and set as current layer, so new plottables/items are put there.
- QCustomPlot::viewport now makes the previously inaccessible viewport rect read-only-accessible (needed that for item-interface)
- PNG export now allows transparent background by calling QCustomPlot::setColor(Qt::transparent) before savePng
- QCPStatisticalBox outlier symbols may now be all scatter symbols, not only hardcoded circles.
- perfect precision of scatter symbol/error bar drawing and clipping in both antialiased and non-antialiased mode, by introducing QCPPainter
that works around some QPainter bugs/inconveniences. Further, more complex symbols like ssCrossSquare used to look crooked, now they look good.
- new antialiasing control system: Each drawing element now has its own "setAntialiased" function to control whether it is drawn antialiased.
- QCustomPlot::setAntialiasedElements and QCustomPlot::setNotAntialiasedElements can be used to override the individual settings.
- Subclasses of QCPAbstractPlottable can now use the convenience functions like applyFillAntialiasingHint or applyScattersAntialiasingHint to
easily make their drawing code comply with the overall antialiasing system.
- QCustomPlot::setNoAntialiasingOnDrag allows greatly improved performance and responsiveness by temporarily disabling all antialiasing while
the user is dragging axis ranges
- QCPGraph can now show scatter symbols at data points and hide its line (see QCPGraph::setScatterStyle, setScatterSize, setScatterPixmap, setLineStyle)
- Grid drawing code was sourced out from QCPAxis to QCPGrid. QCPGrid is mainly an internal class and every QCPAxis owns one. The grid interface still
works through QCPAxis and hasn't changed. The separation allows the grid to be drawn on a different layer as the axes, such that e.g. a graph can
be above the grid but below the axes.
- QCustomPlot::hasPlottable(plottable), returns whether the QCustomPlot contains the plottable
- QCustomPlot::setPlottingHint/setPlottingHints, plotting hints control details about the plotting quality/speed
- export to jpg and bmp added (QCustomPlot::saveJpg/saveBmp), as well as control over compression quality for png and jpg
- multi-select-modifier may now be specified with QCustomPlot::setMultiSelectModifier and is not fixed to Ctrl anymore
Bugfixes:
- fixed QCustomPlot ignores replot after it had size (0,0) even if size becomes valid again
- on Windows, a repaint used to be delayed during dragging/zooming of a complex plot, until the drag operation was done.
This was fixed, i.e. repaints are forced after a replot() call. See QCP::phForceRepaint and setPlottingHints.
- when using the raster paintengine and exporting to scaled PNG, pen widths are now scaled correctly (QPainter bug workaround via QCPPainter)
- PDF export now respects QCustomPlot background color (QCustomPlot::setColor), also Qt::transparent
- fixed a bug on QCPBars and QCPStatisticalBox where auto-rescaling of axis would fail when all data is very small (< 1e-11)
- fixed mouse event propagation bug that prevented range dragging from working on KDE (GNU/Linux)
- fixed a compiler warning on 64-bit systems due to pointer cast to int instead of quintptr in a qDebug output
Other:
- Added support for easier shared library creation (including examples for compiling and using QCustomPlot as shared library)
- QCustomPlot now has the Qt::WA_OpaquePaintEvent widget attribute (gives slightly improved performance).
- QCP::aeGraphs (enum QCP::AntialiasedElement, previously QCustomPlot::aeGraphs) has been marked deprecated since version 02.02.12 and
was now removed. Use QCP::aePlottables instead.
- optional performance-quality-tradeoff for solid graph lines (see QCustomPlot::setPlottingHints).
- marked data classes and QCPRange as Q_MOVABLE_TYPE
- replaced usage of own macro FUNCNAME with Qt macro Q_FUNC_INFO
- QCustomPlot now returns a minimum size hint of 50*50
#### Version released on 31.03.12 ####
Changes that (might) break backward compatibility:
- QCPAbstractLegendItem now inherits from QObject
- mousePress, mouseMove and mouseRelease signals are now emitted before and not after any QCustomPlot processing (range dragging, selecting, etc.)
Added features:
- Interaction system: now allows selecting of objects like plottables, axes, legend and plot title, see QCustomPlot::setInteractions documentation
- Interaction system for plottables:
- setSelectable, setSelected, setSelectedPen, setSelectedBrush, selectTest on QCPAbstractPlottable and all derived plottables
- setSelectionTolerance on QCustomPlot
- selectedPlottables and selectedGraphs on QCustomPlot (returns the list of currently selected plottables/graphs)
- Interaction system for axes:
- setSelectable, setSelected, setSelectedBasePen, setSelectedTickPen, setSelectedSubTickPen, setSelectedLabelFont, setSelectedTickLabelFont,
setSelectedLabelColor, setSelectedTickLabelColor, selectTest on QCPAxis
- selectedAxes on QCustomPlot (returns a list of the axes that currently have selected parts)
- Interaction system for legend:
- setSelectable, setSelected, setSelectedBorderPen, setSelectedIconBorderPen, setSelectedBrush, setSelectedFont, setSelectedTextColor, selectedItems on QCPLegend
- setSelectedFont, setSelectedTextColor, setSelectable, setSelected on QCPAbstractLegendItem
- selectedLegends on QCustomPlot
- Interaction system for title:
- setSelectedTitleFont, setSelectedTitleColor, setTitleSelected on QCustomPlot
- new signals in accordance with the interaction system:
- selectionChangedByUser on QCustomPlot
- selectionChanged on QCPAbstractPlottable
- selectionChanged on QCPAxis
- selectionChanged on QCPLegend and QCPAbstractLegendItem
- plottableClick, legendClick, axisClick, titleClick, plottableDoubleClick, legendDoubleClick, axisDoubleClick, titleDoubleClick on QCustomPlot
- QCustomPlot::deselectAll (deselects everything, i.e. axes and plottables)
- QCPAbstractPlottable::pixelsToCoords (inverse function to the already existing coordsToPixels function)
- QCPRange::contains(double value)
- QCPAxis::setLabelColor and setTickLabelColor
- QCustomPlot::setTitleColor
- QCustomPlot now emits beforeReplot and afterReplot signals. Note that it is safe to make two customPlots mutually call eachothers replot functions
in one of these slots, it will not cause an infinite loop. (usefull for synchronizing axes ranges between two customPlots, because setRange alone doesn't replot)
- If the Qt version is 4.7 or greater, the tick label strings in date-time-mode now support sub-second accuracy (e.g. with format like "hh:mm:ss.zzz").
Bugfixes:
- tick labels/margins should no longer oscillate by one pixel when dragging range or replotting repeatedly while changing e.g. data. This
was caused by a bug in Qt's QFontMetrics::boundingRect function when the font has an integer point size (probably some rounding problem).
The fix hence consists of creating a temporary font (only for bounding-box calculation) which is 0.05pt larger and thus avoiding the
jittering rounding outcome.
- tick label, axis label and plot title colors used to be undefined. This was fixed by providing explicit color properties.
Other:
- fixed some glitches in the documentation
- QCustomPlot::replot and QCustomPlot::rescaleAxes are now slots
#### Version released on 02.02.12 ####
Changes that break backward compatibility:
- renamed all secondary classes from QCustomPlot[...] to QCP[...]:
QCustomPlotAxis -> QCPAxis
QCustomPlotGraph -> QCPGraph
QCustomPlotRange -> QCPRange
QCustomPlotData -> QCPData
QCustomPlotDataMap -> QCPDataMap
QCustomPlotLegend -> QCPLegend
QCustomPlotDataMapIterator -> QCPDataMapIterator
QCustomPlotDataMutableMapIterator -> QCPDataMutableMapIterator
A simple search and replace on all code files should make your code run again, e.g. consider the regex "QCustomPlot(?=[AGRDL])" -> "QCP".
Make sure not to just replace "QCustomPlot" with "QCP" because the main class QCustomPlot hasn't changed to QCP.
This change was necessary because class names became unhandy, pardon my bad naming decision in the beginning.
- QCPAxis::tickLength() and QCPAxis::subTickLength() now each split into two functions for inward and outward ticks (tickLengthIn/tickLengthOut).
- QCPLegend now uses QCPAbstractLegendItem to carry item data (before, the legend was passed QCPGraphs directly)
- QCustomPlot::addGraph() now doesn't return the index of the created graph anymore, but a pointer to the created QCPGraph.
- QCustomPlot::setAutoAddGraphToLegend is replaced by setAutoAddPlottableToLegend
Added features:
- Reversed axis range with QCPAxis::setRangeReversed(bool)
- Tick labels are now only drawn if not clipped by the viewport (widget border) on the sides (e.g. left and right on a horizontal axis).
- Zerolines. Like grid lines only with a separate pen (QCPAxis::setZeroLinePen), at tick position zero.
- Outward ticks. QCPAxis::setTickLength/setSubTickLength now accepts two arguments for inward and outward tick length. This doesn't break
backward compatibility because the second argument (outward) has default value zero and thereby a call with one argument hasn't changed its meaning.
- QCPGraph now inherits from QCPAbstractPlottable
- QCustomPlot::addPlottable/plottable/removePlottable/clearPlottables added to interface with the new QCPAbstractPlottable-based system. The simpler interface
which only acts on QCPGraphs (addGraph, graph, removeGraph, etc.) was adapted internally and is kept for backward compatibility and ease of use.
- QCPLegend items for plottables (e.g. graphs) can automatically wrap their texts to fit the widths, see QCPLegend::setMinimumSize and QCPPlottableLegendItem::setTextWrap.
- QCustomPlot::rescaleAxes. Adapts axis ranges to show all plottables/graphs, by calling QCPAbstractPlottable::rescaleAxes on all plottables in the plot.
- QCPCurve. For plotting of parametric curves.
- QCPBars. For plotting of bar charts.
- QCPStatisticalBox. For statistical box plots.
Bugfixes:
- Fixed QCustomPlot::removeGraph(int) not being able to remove graph index 0
- made QCustomPlot::replot() abort painting when painter initialization fails (e.g. because width/height of QCustomPlot is zero)
- The distance of the axis label from the axis ignored the tick label padding, this could have caused overlapping axis labels and tick labels
- fixed memory leak in QCustomPlot (dtor didn't delete legend)
- fixed bug that prevented QCPAxis::setRangeLower/Upper from setting the value to exactly 0.
Other:
- Changed default error bar handle size (QCustomPlotGraph::setErrorBarSize) from 4 to 6.
- Removed QCustomPlotDataFetcher. Was deprecated and not used class.
- Extended documentation, especially class descriptions.
#### Version released on 15.01.12 ####
Changes that (might) break backward compatibility:
- QCustomPlotGraph now inherits from QObject
Added features:
- Added axis background pixmap (QCustomPlot::setAxisBackground, setAxisBackgroundScaled, setAxisBackgroundScaledMode)
- Added width and height parameter on PDF export function QCustomPlot::savePdf(). This now allows PDF export to
have arbitrary dimensions, independent of the current geometry of the QCustomPlot.
- Added overload of QCustomPlot::removeGraph that takes QCustomPlotGraph* as parameter, instead the index of the graph
- Added all enums to the Qt meta system via Q_ENUMS(). The enums can now be transformed
to QString values easily with the Qt meta system, which makes saving state e.g. as XML
significantly nicer.
- added typedef QMapIterator<double,QCustomPlotData> QCustomPlotDataMapIterator
and typedef QMutableMapIterator<double,QCustomPlotData> QCustomPlotDataMutableMapIterator
for improved information hiding, when using iterators outside QCustomPlot code
Bugfixes:
- Fixed savePngScaled. Axis/label drawing functions used to reset the painter transform
and thereby break savePngScaled. Now they buffer the current transform and restore it afterwards.
- Fixed some glitches in the doxygen comments (affects documentation only)
Other:
- Changed the default tickLabelPadding of top axis from 3 to 6 pixels. Looks better.
- Changed the default QCustomPlot::setAntialiasedElements setting: Graph fills are now antialiased
by default. That's a bit slower, but makes fill borders look better.
#### Version released on 19.11.11 ####
Changes that break backward compatibility:
- QCustomPlotAxis: tickFont and setTickFont renamed to tickLabelFont and setTickLabelFont (for naming consistency)
Other:
- QCustomPlotAxis: Added rotated tick labels, see setTickLabelRotation

View File

@@ -0,0 +1,139 @@
// Display a .dot graph
// Author: Max Schwarz <max.schwarz@uni-bonn.de>
#include "dot_widget.h"
#include <unistd.h>
#include <fcntl.h>
#include <stdexcept>
#include <sys/wait.h>
#include <QPainter>
static ssize_t runDot(const std::string& dot, int width, int height, uint8_t* pngOut, size_t pngOutSize)
{
int inputPipe[2];
int outputPipe[2];
if(pipe(inputPipe) != 0 || pipe(outputPipe) != 0)
throw std::runtime_error("Could not create pipe");
int pid = fork();
if(pid == 0)
{
// Child
close(inputPipe[1]);
close(outputPipe[0]);
dup2(inputPipe[0], STDIN_FILENO);
dup2(outputPipe[1], STDOUT_FILENO);
char sizeBuf[256];
int dpi = 400;
snprintf(sizeBuf, sizeof(sizeBuf), "-Gsize=%f,%f", ((float)width)/dpi, ((float)height)/dpi);
if(execlp("dot", "dot", "-Tpng", sizeBuf, "-Gdpi=400", "/dev/stdin", (char*)NULL) != 0)
{
perror("execlp() failed");
throw std::runtime_error("Could not execute dot");
exit(1);
}
// Cannot reach this
return -1;
}
else
{
// Parent
close(inputPipe[0]);
close(outputPipe[1]);
size_t written = 0;
size_t len = dot.length();
while(written != len)
{
int ret = write(inputPipe[1], dot.c_str() + written, len - written);
if(ret <= 0)
perror("Could not write");
written += ret;
}
close(inputPipe[1]);
size_t readBytes = 0;
while(1)
{
if(pngOutSize == readBytes)
{
throw std::runtime_error("png buffer is to small");
}
int ret = read(outputPipe[0], pngOut + readBytes, pngOutSize - readBytes);
if(ret == 0)
break;
else if(ret < 0)
{
perror("Could not read");
throw std::runtime_error("Could not read");
}
readBytes += ret;
}
close(outputPipe[0]);
int status;
waitpid(pid, &status, 0);
if(status != 0)
fprintf(stderr, "dot exited with error status %d\n", status);
return readBytes;
}
}
namespace nimbro_topic_transport
{
DotWidget::DotWidget()
: m_pngBuf(1024 * 1024)
{
}
DotWidget::~DotWidget()
{
}
void DotWidget::paintEvent(QPaintEvent*)
{
QPainter painter(this);
painter.fillRect(rect(), Qt::white);
painter.setRenderHint(QPainter::SmoothPixmapTransform);
float scale_x = ((float)width()) / m_pixmap.width();
float scale_y = ((float)height()) / m_pixmap.height();
if(scale_x > scale_y)
{
int newWidth = scale_y * m_pixmap.width();
QRect pixmapRect((width() - newWidth)/2, 0, newWidth, height());
painter.drawPixmap(pixmapRect, m_pixmap);
}
else
{
int newHeight = scale_x * m_pixmap.height();
QRect pixmapRect(0, (height() - newHeight)/2, width(), newHeight);
painter.drawPixmap(pixmapRect, m_pixmap);
}
}
void DotWidget::updateGraph(const std::string& dot)
{
ssize_t pngSize = runDot(dot, width(), height(), m_pngBuf.data(), m_pngBuf.size());
m_pixmap.loadFromData(m_pngBuf.data(), pngSize, "png");
update();
}
}

Some files were not shown because too many files have changed in this diff Show More