Skip to content
This repository has been archived by the owner on Dec 1, 2020. It is now read-only.

Commit

Permalink
Merge pull request #29 from project-march/release/v0.3.0
Browse files Browse the repository at this point in the history
Release v0.3.0
  • Loading branch information
RutgerVanBeek authored Mar 16, 2020
2 parents 5c5b738 + cb78593 commit d67e705
Show file tree
Hide file tree
Showing 16 changed files with 209 additions and 25 deletions.
7 changes: 7 additions & 0 deletions .coveragerc
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
[report]
include =
*march_rqt_gait_selection*
*march_rqt_input_device*
*march_rqt_note_taker*
omit =
*__init__.py
2 changes: 1 addition & 1 deletion .flake8
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
show-source = true
max-line-length = 120
format = ${cyan}%(path)s${reset}:${yellow_bold}%(row)d${reset}:${green_bold}%(col)d${reset}: ${red_bold}%(code)s${reset} %(text)s
exclude = .git
exclude = .git, __init__.py
application-package-names =
march_rqt_gait_selection,
march_rqt_input_device,
Expand Down
4 changes: 4 additions & 0 deletions .rosinstall
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
- git:
local-name: march
uri: https://github.com/project-march/march
version: develop
7 changes: 7 additions & 0 deletions .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,14 @@ git:
env:
global:
- ROS_REPO=ros
- ADDITIONAL_DEBS=curl
- BUILDER=colcon
- CATKIN_LINT=pedantic
- CI_ENV=`bash <(curl -s https://codecov.io/env)`
- DOCKER_RUN_OPTS='$CI_ENV -e CATKIN_TEST_COVERAGE=1 -e NOSE_COVER_INCLUSIVE=True -e NOSE_COVER_BRANCHES=True'
- AFTER_INSTALL_TARGET_DEPENDENCIES='pip install coverage'
- AFTER_RUN_TARGET_TEST='cd "$target_ws" && ./src/monitor/coverage.sh && bash <(curl -s https://codecov.io/bash) -R src/monitor -F test && bash <(curl -s https://codecov.io/bash) -R src/monitor -F production'
- UPSTREAM_WORKSPACE='.rosinstall -march/march_data_collector -march/march_description -march/march_gain_scheduling -march/march_gait_scheduler -march/march_gait_selection -march/march_launch -march/march_safety -march/march_shared_classes -march/march_state_machine'

jobs:
include:
Expand All @@ -37,5 +43,6 @@ jobs:
# clone and run industrial_ci
install:
- git clone --quiet --depth 1 https://github.com/ros-industrial/industrial_ci.git .industrial_ci -b master

script:
- .industrial_ci/travis.sh
1 change: 1 addition & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@
Monitor RQt plugins for the March exoskeleton

![GitHub release (latest by date including pre-releases)](https://img.shields.io/github/v/release/project-march/monitor?include_prereleases)
[![codecov](https://codecov.io/gh/project-march/monitor/branch/master/graph/badge.svg?flag=production)](https://codecov.io/gh/project-march/monitor)

| Branch | Build Status |
| ------ |:------------:|
Expand Down
17 changes: 17 additions & 0 deletions codecov.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
coverage:
status:
project:
default: off
production:
target: auto
flags:
- production
fixes:
- "src/monitor/::"
flags:
production:
paths:
- "*/src/**/*"
test:
paths:
- "*/test/*"
5 changes: 5 additions & 0 deletions coverage.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
#!/usr/bin/env sh

cd build/march_rqt_note_taker || return
coverage xml --rcfile ../../src/monitor/.coveragerc
cd ../.. || return
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,10 @@ def __init__(self, context):
self.create_button('gait_walk_small', image_path='/gait_walk_small.png',
callback=lambda: self.controller.publish_gait('gait_walk_small'))

gait_walk_large = \
self.create_button('gait_walk_large',
callback=lambda: self.controller.publish_gait('gait_walk_large'))

gait_single_step_small = \
self.create_button('gait_single_step_small', image_path='/gait_single_step_small.png',
callback=lambda: self.controller.publish_gait('gait_single_step_small'))
Expand Down Expand Up @@ -112,6 +116,14 @@ def __init__(self, context):
self.create_button('gait_stairs_down', image_path='/gait_stairs_down.png',
callback=lambda: self.controller.publish_gait('gait_stairs_down'))

gait_stairs_up_single_step = \
self.create_button('gait_stairs_up_single_step',
callback=lambda: self.controller.publish_gait('gait_stairs_up_single_step'))

gait_stairs_down_single_step = \
self.create_button('gait_stairs_down_single_step',
callback=lambda: self.controller.publish_gait('gait_stairs_down_single_step'))

gait_rough_terrain_high_step = \
self.create_button('gait_rough_terrain_high_step',
callback=lambda: self.controller.publish_gait('gait_rough_terrain_high_step'))
Expand All @@ -120,6 +132,18 @@ def __init__(self, context):
self.create_button('gait_rough_terrain_middle_steps',
callback=lambda: self.controller.publish_gait('gait_rough_terrain_middle_steps'))

gait_rough_terrain_first_middle_step = \
self.create_button('gait_rough_terrain_first_middle_step',
callback=lambda: self.controller.publish_gait('gait_rough_terrain_first_middle_step'))

gait_rough_terrain_second_middle_step = \
self.create_button('gait_rough_terrain_second_middle_step',
callback=lambda: self.controller.publish_gait('gait_rough_terrain_second_middle_step'))

gait_rough_terrain_third_middle_step = \
self.create_button('gait_rough_terrain_third_middle_step',
callback=lambda: self.controller.publish_gait('gait_rough_terrain_third_middle_step'))

gait_ramp_door_slope_up = \
self.create_button('gait_ramp_door_slope_up',
callback=lambda: self.controller.publish_gait('gait_ramp_door_slope_up'))
Expand All @@ -132,13 +156,37 @@ def __init__(self, context):
self.create_button('gait_ramp_door_last_step',
callback=lambda: self.controller.publish_gait('gait_ramp_door_last_step'))

gait_tilted_path_straight_start_right = \
self.create_button('gait_tilted_path_straight_start_right',
callback=lambda: self.controller.publish_gait('gait_tilted_path_straight_start_right'))
gait_tilted_path_left_straight_start = \
self.create_button('gait_tilted_path_left_straight_start',
callback=lambda: self.controller.publish_gait('gait_tilted_path_left_straight_start'))

gait_tilted_path_left_single_step = \
self.create_button('gait_tilted_path_left_single_step',
callback=lambda: self.controller.publish_gait('gait_tilted_path_left_single_step'))

gait_tilted_path_left_straight_end = \
self.create_button('gait_tilted_path_left_straight_end',
callback=lambda: self.controller.publish_gait('gait_tilted_path_left_straight_end'))

gait_tilted_path_left_flexed_knee_step = \
self.create_button('gait_tilted_path_left_flexed_knee_step',
callback=lambda: self.controller.publish_gait('gait_tilted_path_left_flexed_knee_step'))

gait_tilted_path_straight_start_left = \
self.create_button('gait_tilted_path_straight_start_left',
callback=lambda: self.controller.publish_gait('gait_tilted_path_straight_start_left'))
gait_tilted_path_right_straight_start = \
self.create_button('gait_tilted_path_right_straight_start',
callback=lambda: self.controller.publish_gait('gait_tilted_path_right_straight_start'))

gait_tilted_path_right_single_step = \
self.create_button('gait_tilted_path_right_single_step',
callback=lambda: self.controller.publish_gait('gait_tilted_path_right_single_step'))

gait_tilted_path_right_straight_end = \
self.create_button('gait_tilted_path_right_straight_end',
callback=lambda: self.controller.publish_gait('gait_tilted_path_right_straight_end'))

gait_tilted_path_right_flexed_knee_step = \
self.create_button('gait_tilted_path_right_flexed_knee_step',
callback=lambda: self.controller.publish_gait('gait_tilted_path_right_flexed_knee_step'))

gait_tilted_path_first_start = \
self.create_button('gait_tilted_path_first_start',
Expand All @@ -148,6 +196,14 @@ def __init__(self, context):
self.create_button('gait_tilted_path_second_start',
callback=lambda: self.controller.publish_gait('gait_tilted_path_second_start'))

gait_tilted_path_first_end = \
self.create_button('gait_tilted_path_first_end',
callback=lambda: self.controller.publish_gait('gait_tilted_path_first_end'))

gait_tilted_path_second_end = \
self.create_button('gait_tilted_path_second_end',
callback=lambda: self.controller.publish_gait('gait_tilted_path_second_end'))

stop_button = self.create_button('gait_stop', image_path='/stop.png',
callback=lambda: self.controller.publish_stop())

Expand All @@ -164,20 +220,29 @@ def __init__(self, context):
# Position in the array determines position on screen.
march_button_layout = [

[home_sit, home_stand, gait_walk, gait_walk_small, stop_button, pause_button],
[home_sit, home_stand, gait_walk, gait_walk_small, gait_walk_large, stop_button, pause_button],

[gait_sit, gait_stand, gait_single_step_normal, gait_single_step_small, continue_button, error_button],

[gait_sofa_sit, gait_sofa_stand, gait_stairs_up, gait_stairs_down, rocker_switch_increment,
rocker_switch_decrement],
[gait_sofa_sit, gait_sofa_stand, rocker_switch_increment, rocker_switch_decrement],

[gait_stairs_up, gait_stairs_down, gait_stairs_up_single_step, gait_stairs_down_single_step],

[gait_side_step_left, gait_side_step_right, gait_side_step_left_small, gait_side_step_right_small],

[gait_rough_terrain_high_step, gait_rough_terrain_middle_steps, gait_ramp_door_slope_up,
gait_ramp_door_slope_down, gait_ramp_door_last_step],
[gait_rough_terrain_high_step, gait_rough_terrain_middle_steps, gait_rough_terrain_first_middle_step,
gait_rough_terrain_second_middle_step, gait_rough_terrain_third_middle_step],

[gait_ramp_door_slope_up, gait_ramp_door_slope_down, gait_ramp_door_last_step],

[gait_tilted_path_left_straight_start, gait_tilted_path_left_single_step,
gait_tilted_path_left_straight_end, gait_tilted_path_left_flexed_knee_step],

[gait_tilted_path_right_straight_start, gait_tilted_path_right_single_step,
gait_tilted_path_right_straight_end, gait_tilted_path_right_flexed_knee_step],

[gait_tilted_path_straight_start_right, gait_tilted_path_straight_start_left, gait_tilted_path_first_start,
gait_tilted_path_second_start],
[gait_tilted_path_first_start, gait_tilted_path_second_start, gait_tilted_path_first_end,
gait_tilted_path_second_end],
]

# Create the qt_layout from the button layout.
Expand Down
4 changes: 2 additions & 2 deletions march_rqt_note_taker/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
cmake_minimum_required(VERSION 2.8.3)
project(march_rqt_note_taker)

find_package(catkin REQUIRED)
find_package(catkin REQUIRED COMPONENTS march_shared_resources std_msgs)

catkin_python_setup()
catkin_package()
catkin_package(CATKIN_DEPENDS march_shared_resources std_msgs)

install(FILES plugin.xml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
Expand Down
3 changes: 3 additions & 0 deletions march_rqt_note_taker/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,9 @@

<buildtool_depend>catkin</buildtool_depend>

<depend>std_msgs</depend>
<depend>march_shared_resources</depend>

<exec_depend>rospy</exec_depend>
<exec_depend>rqt_gui</exec_depend>
<exec_depend>rqt_gui_py</exec_depend>
Expand Down
4 changes: 2 additions & 2 deletions march_rqt_note_taker/src/march_rqt_note_taker/entry.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,11 @@

class Entry(QObject):

def __init__(self, content, date_time=QDateTime.currentDateTime(), is_error=False):
def __init__(self, content, date_time=None, is_error=False):
super(Entry, self).__init__()

self.content = content
self.date_time = date_time
self.date_time = QDateTime.currentDateTime() if date_time is None else date_time
self.is_error = is_error

@classmethod
Expand Down
42 changes: 38 additions & 4 deletions march_rqt_note_taker/src/march_rqt_note_taker/notes_plugin.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,15 @@
import ast
import os

from qt_gui.plugin import Plugin
from rosgraph_msgs.msg import Log
import rospkg
import rospy
from std_msgs.msg import String

from march_shared_resources.srv import Trigger

from .entry import Entry
from .entry_model import EntryModel
from .filter_map import FilterMap
from .notes_widget import NotesWidget
Expand All @@ -24,14 +29,43 @@ def __init__(self, context):
self._filter_map = FilterMap()
self._filter_map.add_filter(lambda l: l.level >= Log.ERROR)
self._filter_map.add_filter_info_level(lambda l: l.msg == 'March is fully operational')
self._subscriber = rospy.Subscriber('/rosout_agg',
Log,
self._rosout_cb)

self._subscribers = []
self._subscribers.append(rospy.Subscriber('/rosout_agg',
Log,
self._rosout_cb))
self._subscribers.append(rospy.Subscriber('/march/gait/current',
String,
self._current_gait_cb))

self._get_gait_version_map = rospy.ServiceProxy('/march/gait_selection/get_version_map',
Trigger)

def shutdown_plugin(self):
self._subscriber.unregister()
for subscriber in self._subscribers:
subscriber.unregister()

def _rosout_cb(self, log_msg):
mapped_msg = self._filter_map(log_msg)
if mapped_msg:
self._model.insert_log_msg(mapped_msg)

def _current_gait_cb(self, current_gait):
"""
Inserts an entry, which logs the current gait version used.
:type current_gait: String
:param current_gait: Current gait goal being executed
"""
try:
gait_version_map = ast.literal_eval(self._get_gait_version_map().message)

message = 'Starting gait {0}: {1}'.format(current_gait.data,
str(gait_version_map[current_gait.data]))
self._model.insert_row(Entry(message))
except rospy.ServiceException as e:
rospy.logwarn('Failed to contact gait selection node for gait versions: {0}'.format(e))
except KeyError:
pass
except ValueError as e:
rospy.logerr('Failed to parse gait version map: {0}'.format(e))
5 changes: 5 additions & 0 deletions march_rqt_note_taker/test/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
from march_rqt_note_taker.entry import Entry
from march_rqt_note_taker.entry_model import EntryModel
from march_rqt_note_taker.filter_map import FilterMap
from march_rqt_note_taker.notes_plugin import NotesPlugin
from march_rqt_note_taker.notes_widget import NotesWidget
30 changes: 28 additions & 2 deletions march_rqt_note_taker/test/entry_model_test.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
import unittest

from python_qt_binding.QtCore import QDateTime, Qt
from rosgraph_msgs.msg import Log

from march_rqt_note_taker.entry import Entry
Expand All @@ -14,10 +15,24 @@ def test_empty_model(self):
self.assertEqual(self.model.rowCount(), 0)
self.assertEqual(self.model.columnCount(), 2)

def test_insert_single_row(self):
self.model.insert_row(Entry('test'))
def test_horizontal_model_header(self):
self.assertEqual(self.model.headerData(0, Qt.Horizontal, Qt.DisplayRole), 'Time')
self.assertEqual(self.model.headerData(1, Qt.Horizontal, Qt.DisplayRole), 'Entry')

def test_insert_single_row_count(self):
entry = Entry('test', QDateTime.fromSecsSinceEpoch(5))
self.model.insert_row(entry)
self.assertEqual(self.model.rowCount(), 1)

def test_insert_single_row(self):
entry = Entry('test', QDateTime.fromSecsSinceEpoch(5))
self.model.insert_row(entry)

time_index = self.model.createIndex(0, 0)
content_index = self.model.createIndex(0, 1)
self.assertEqual(self.model.data(time_index), entry.time_string())
self.assertEqual(self.model.data(content_index), entry.content)

def test_insert_multiple_row(self):
self.model.insert_row(Entry('test1'))
self.model.insert_row(Entry('test2'))
Expand Down Expand Up @@ -61,3 +76,14 @@ def test_get_row_out_of_bounds(self):

def test_get_column_out_of_bounds(self):
self.assertIsNone(self.model.data(self.model.createIndex(0, len(self.model.columns))))

def test_empty_model_to_string(self):
self.assertEqual(str(self.model), '')

def test_entry_model_to_string(self):
entry = Entry('test1', QDateTime.fromSecsSinceEpoch(5))
self.model.insert_row(entry)
self.model.insert_row(entry)
self.model.insert_row(entry)

self.assertEqual(str(self.model), '{0}\n{0}\n{0}'.format(entry))
7 changes: 6 additions & 1 deletion march_rqt_note_taker/test/entry_test.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
import unittest

from python_qt_binding.QtCore import QDateTime
from python_qt_binding.QtCore import QDateTime, QTimeZone
from rosgraph_msgs.msg import Log
import rospy

Expand Down Expand Up @@ -56,3 +56,8 @@ def test_to_string(self):
entry = Entry(content, date_time)
self.assertEqual(str(entry),
'[{0}] {1}'.format(date_time.toString(), content))

def test_to_time_string(self):
date_time = QDateTime.fromSecsSinceEpoch(5, QTimeZone.utc())
entry = Entry('', date_time)
self.assertEqual(entry.time_string(), '00:00:05')
Loading

0 comments on commit d67e705

Please sign in to comment.