Skip to content

Commit

Permalink
Merge pull request #90 from RI-SE/feature_triggerClassDefinition
Browse files Browse the repository at this point in the history
Feature trigger class definition
  • Loading branch information
LukasWikander authored Jul 9, 2019
2 parents 079f25d + 2135840 commit b8cc7ee
Show file tree
Hide file tree
Showing 8 changed files with 531 additions and 10 deletions.
29 changes: 20 additions & 9 deletions modules/ScenarioControl/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,10 +1,12 @@
cmake_minimum_required(VERSION 2.8)
set (CMAKE_CXX_STANDARD 11)

project(ScenarioControl)
# This module is an example of how to set up a new module external to the Maestro executable


include_directories(inc)
include_directories(src)
include_directories(../../util/C/logging)
include_directories(../../util/C/time)
include_directories(../../util/C/MQBus)
Expand All @@ -14,31 +16,40 @@ include(GNUInstallDirs)

# Create library
add_library(MaestroLogging
../../util/C/logging/logging.h
../../util/C/logging/logging.c
../../util/C/logging/logging.h
../../util/C/logging/logging.c
)

add_library(MaestroTime
../../util/C/time/maestroTime.h
../../util/C/time/maestroTime.c
../../util/C/time/maestroTime.h
../../util/C/time/maestroTime.c
)

add_library(MQBus
../../util/C/MQBus/mqbus.h
../../util/C/MQBus/mqbus.c
../../util/C/MQBus/mqbus.h
../../util/C/MQBus/mqbus.c
)

# Create library
add_library(util
../../server/src/util.c
../../server/inc/util.h
../../server/src/util.c
../../server/inc/util.h
)

add_library(Trigger
inc/trigger.h
src/trigger.cpp
inc/booleantrigger.h
src/booleantrigger.cpp
inc/braketrigger.h
src/braketrigger.cpp
)

add_executable(ScenarioControl src/main.cpp)

install(TARGETS ScenarioControl DESTINATION bin)

target_link_libraries(ScenarioControl MaestroTime MaestroLogging util)
target_link_libraries(ScenarioControl MaestroTime MaestroLogging util Trigger)
target_link_libraries(util MQBus MaestroTime MaestroLogging)
target_link_libraries(MQBus rt m)

Expand Down
2 changes: 1 addition & 1 deletion modules/ScenarioControl/README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
## Dummy module
## ScenarioControl module
TODO.

### Build process
Expand Down
48 changes: 48 additions & 0 deletions modules/ScenarioControl/inc/booleantrigger.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
#ifndef BOOLEANTRIGGER_H
#define BOOLEANTRIGGER_H

#include "trigger.h"

#include <vector>
#include <set>

class BooleanTrigger : public Trigger
{
public:
using Trigger::Trigger;

virtual TriggerReturnCode_t parseParameters() override = 0;

TriggerReturnCode_t update(bool) override;

protected:
TriggerReturnCode_t checkIfTriggered(void) override;

enum TriggerMode {
INVALID_MODE,
HIGH,
LOW,
EDGE_RISING,
EDGE_FALLING,
EDGE_ANY}
mode = INVALID_MODE;

bool isStateTrue = false, wasStateTrue = false;

private:

virtual std::set<Trigger::TriggerParameter_t> getAcceptedParameters() override
{
return {
Trigger::TRIGGER_PARAMETER_FALSE,
Trigger::TRIGGER_PARAMETER_TRUE,
Trigger::TRIGGER_PARAMETER_RISING_EDGE,
Trigger::TRIGGER_PARAMETER_FALLING_EDGE,
Trigger::TRIGGER_PARAMETER_ANY_EDGE
};
}


};

#endif // BOOLEANTRIGGER_H
33 changes: 33 additions & 0 deletions modules/ScenarioControl/inc/braketrigger.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
#ifndef BRAKETRIGGER_H
#define BRAKETRIGGER_H

#include "booleantrigger.h"

#include <set>
#include <vector>

class BrakeTrigger : public BooleanTrigger
{
public:
BrakeTrigger(TriggerID_t triggerID);
TriggerReturnCode_t parseParameters() override;

private:
std::vector<TriggerParameter_t> parameters;

std::set<Trigger::TriggerParameter_t> getAcceptedParameters() override
{
return {
Trigger::TRIGGER_PARAMETER_FALSE,
Trigger::TRIGGER_PARAMETER_TRUE,
Trigger::TRIGGER_PARAMETER_RELEASED,
Trigger::TRIGGER_PARAMETER_PRESSED,
Trigger::TRIGGER_PARAMETER_LOW,
Trigger::TRIGGER_PARAMETER_HIGH,
Trigger::TRIGGER_PARAMETER_RISING_EDGE,
Trigger::TRIGGER_PARAMETER_FALLING_EDGE,
Trigger::TRIGGER_PARAMETER_ANY_EDGE
};
}
};
#endif // BRAKETRIGGER_H
151 changes: 151 additions & 0 deletions modules/ScenarioControl/inc/trigger.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,151 @@
#ifndef TRIGGER_H
#define TRIGGER_H

#include <cstdint>
#include <set>
#include <iostream>
#include <vector>



class Trigger
{
public:
/*! Typedefs */
typedef enum {
TRIGGER_UNDEFINED = 0x0000,
TRIGGER_TYPE_1 = 0x0001,
TRIGGER_SPEED = 0x0010,
TRIGGER_DISTANCE = 0x0020,
TRIGGER_ACCELERATION = 0x0030,
TRIGGER_LANE_CHANGED = 0x0040,
TRIGGER_LANE_OFFSET = 0x0050,
TRIGGER_POSITION_REACHED = 0x0060,
TRIGGER_POSITION_LEFT = 0x0061,
TRIGGER_POSITION_OFFSET = 0x0062,
TRIGGER_STEERING_ANGLE = 0x0070,
TRIGGER_THROTTLE_VALUE = 0x0080,
TRIGGER_BRAKE = 0x0090,
TRIGGER_ACTIVE_TRAJECTORY = 0x00A0,
TRIGGER_OTHER_OBJECT_FEATURE = 0x00B0,
TRIGGER_INFRASTRUCTURE = 0x00C0,
TRIGGER_TEST_SCENARIO_EVENT = 0x00D0,
TRIGGER_MISC_DIGITAL_INPUT = 0x00E0,
TRIGGER_MISC_ANALOG_INPUT = 0x00F0,
TRIGGER_TIMER_EVENT_OCCURRED = 0x0100,
TRIGGER_MODE_CHANGED = 0x0110,
TRIGGER_UNAVAILABLE = 0xFFFF
} TriggerTypeCode_t;

typedef enum {
TRIGGER_PARAMETER_FALSE = 0x00000000,
TRIGGER_PARAMETER_TRUE = 0x00000001,
TRIGGER_PARAMETER_RELEASED = 0x00000010,
TRIGGER_PARAMETER_PRESSED = 0x00000011,
TRIGGER_PARAMETER_LOW = 0x00000020,
TRIGGER_PARAMETER_HIGH = 0x00000021,
TRIGGER_PARAMETER_RISING_EDGE = 0x00000022,
TRIGGER_PARAMETER_FALLING_EDGE = 0x00000023,
TRIGGER_PARAMETER_ANY_EDGE = 0x00000024,
TRIGGER_PARAMETER_RELATIVE = 0x00000030,
TRIGGER_PARAMETER_ABSOLUTE = 0x00000031,
TRIGGER_PARAMETER_VALUE = 0x00000040,
TRIGGER_PARAMETER_MIN = 0x00000050,
TRIGGER_PARAMETER_MAX = 0x00000051,
TRIGGER_PARAMETER_MEAN = 0x00000052,
TRIGGER_PARAMETER_EQUAL_TO = 0x00000060,
TRIGGER_PARAMETER_GREATER_THAN = 0x00000061,
TRIGGER_PARAMETER_GREATER_THAN_OR_EQUAL_TO = 0x00000062,
TRIGGER_PARAMETER_LESS_THAN = 0x00000063,
TRIGGER_PARAMETER_LESS_THAN_OR_EQUAL_TO = 0x00000064,
TRIGGER_PARAMETER_NOT_EQUAL_TO = 0x00000065,
TRIGGER_PARAMETER_X = 0x00000070,
TRIGGER_PARAMETER_Y = 0x00000071,
TRIGGER_PARAMETER_Z = 0x00000072,
TRIGGER_PARAMETER_TIME = 0x00000080,
TRIGGER_PARAMETER_DATE = 0x00000081,
TRIGGER_PARAMETER_RULE = 0x000000A0,
TRIGGER_PARAMETER_UNAVAILABLE = 0xFFFFFFFF
} TriggerParameter_t;

typedef uint16_t TriggerID_t;

typedef enum {
OK,
NOT_OK,
INVALID_ARGUMENT,
TRIGGER_OCCURRED,
NO_TRIGGER_OCCURRED
} TriggerReturnCode_t;


/*! Constructor */
Trigger(TriggerID_t triggerID, TriggerTypeCode_t triggerType);


/*! Destructor */
virtual ~Trigger();


/*! Getters */
virtual TriggerTypeCode_t getTypeCode() { return triggerTypeCode; }
uint16_t getID() { return triggerID; }
std::vector<TriggerParameter_t> getParameters() { return parameters; }


/*! Setters */
void setID(uint16_t triggerID) { this->triggerID = triggerID; }

/*!
* \brief appendParameter Appends an ISO parameter to the parameters list.
* \param triggerParameter Parameter to append
* \return Value according to ::TriggerReturnCode_t
*/
TriggerReturnCode_t appendParameter(TriggerParameter_t triggerParameter);

/*!
* \brief parseParameters Parse the parameters list into an appropriate Trigger mode.
* \return Value according to ::TriggerReturnCode_t
*/
virtual TriggerReturnCode_t parseParameters() = 0;


/*! To string */
friend std::ostream& operator<<(std::ostream &strm, Trigger &trig) {
return strm << "TRIGGER ID " << trig.triggerID <<
" TYPE " << getTypeAsString(trig.getTypeCode()) <<
" PARAMETERS " << trig.getParametersString();
}

static std::string getTypeAsString(TriggerTypeCode_t typeCode);
static std::string getParameterAsString(TriggerParameter_t param);
std::string getParametersString();

/*!
* \brief update Update tracked signal (i.e. signal which causes the trigger to occur).
* Inheriting classes should override the appropriate function(s)
* - e.g. a trigger tracking a floating point trigger should override
* update(float) and update(double)
*/
virtual TriggerReturnCode_t update(void) { return INVALID_ARGUMENT; }
virtual TriggerReturnCode_t update(bool) { return INVALID_ARGUMENT; }
virtual TriggerReturnCode_t update(char) { return INVALID_ARGUMENT; }
virtual TriggerReturnCode_t update(int) { return INVALID_ARGUMENT; }
virtual TriggerReturnCode_t update(float) { return INVALID_ARGUMENT; }
virtual TriggerReturnCode_t update(double) { return INVALID_ARGUMENT; }

protected:
TriggerReturnCode_t checkTriggerParameter(TriggerParameter_t triggerParameter);
TriggerTypeCode_t triggerTypeCode;

private:
TriggerID_t triggerID;
std::vector<TriggerParameter_t> parameters;

virtual std::set<TriggerParameter_t> getAcceptedParameters()
{ return {TRIGGER_PARAMETER_UNAVAILABLE}; }

virtual TriggerReturnCode_t checkIfTriggered(void) = 0;
};

#endif // TRIGGER_H
37 changes: 37 additions & 0 deletions modules/ScenarioControl/src/booleantrigger.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
#include "booleantrigger.h"

/*!
* \brief BooleanTrigger::update Updates the tracked signal (i.e. which causes the trigger) to the value specified
* \param isBrakeCurrentlyPressed Boolean describing if the boolean
* \return Value according to ::TriggerReturnCode_t
*/
Trigger::TriggerReturnCode_t BooleanTrigger::update(bool currentStateValue)
{
wasStateTrue = isStateTrue;
isStateTrue = currentStateValue;
return checkIfTriggered();
}

/*!
* \brief BooleanTrigger::checkIfTriggered Check if the trigger has occurred based on the mode and state
* \return Value according to ::TriggerReturnCode_t
*/
Trigger::TriggerReturnCode_t BooleanTrigger::checkIfTriggered()
{
switch (mode) {
case HIGH:
return isStateTrue ? TRIGGER_OCCURRED : NO_TRIGGER_OCCURRED;
case LOW:
return !isStateTrue ? TRIGGER_OCCURRED : NO_TRIGGER_OCCURRED;
case EDGE_ANY:
return (isStateTrue != wasStateTrue) ? TRIGGER_OCCURRED : NO_TRIGGER_OCCURRED;
case EDGE_RISING:
return (isStateTrue && !wasStateTrue) ? TRIGGER_OCCURRED : NO_TRIGGER_OCCURRED;
case EDGE_FALLING:
return (!isStateTrue && wasStateTrue) ? TRIGGER_OCCURRED : NO_TRIGGER_OCCURRED;
case INVALID_MODE:
return NOT_OK;
}
}


52 changes: 52 additions & 0 deletions modules/ScenarioControl/src/braketrigger.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@

#include "braketrigger.h"

BrakeTrigger::BrakeTrigger(Trigger::TriggerID_t triggerID) : BooleanTrigger(triggerID, Trigger::TRIGGER_BRAKE) { }

/*!
* \brief BooleanTrigger::parseParameters Parses the parameter vector and sets the trigger mode accordingly
* \return Value according to ::TriggerReturnCode_t
*/
Trigger::TriggerReturnCode_t BrakeTrigger::parseParameters()
{
if (parameters.size() == 1)
{
switch (parameters.front())
{
case TRIGGER_PARAMETER_PRESSED:
case TRIGGER_PARAMETER_TRUE:
case TRIGGER_PARAMETER_HIGH:
mode = HIGH;
isStateTrue = false;
wasStateTrue = false;
return OK;
case TRIGGER_PARAMETER_RELEASED:
case TRIGGER_PARAMETER_FALSE:
case TRIGGER_PARAMETER_LOW:
mode = LOW;
isStateTrue = true;
wasStateTrue = true;
return OK;
case TRIGGER_PARAMETER_RISING_EDGE:
mode = EDGE_RISING;
isStateTrue = false;
wasStateTrue = false;
return OK;
case TRIGGER_PARAMETER_FALLING_EDGE:
mode = EDGE_FALLING;
isStateTrue = false;
wasStateTrue = false;
return OK;
case TRIGGER_PARAMETER_ANY_EDGE:
mode = EDGE_ANY;
isStateTrue = false;
wasStateTrue = false;
return OK;
default:
return INVALID_ARGUMENT;
}
}
else return INVALID_ARGUMENT;
}


Loading

0 comments on commit b8cc7ee

Please sign in to comment.