Skip to content
Snippets Groups Projects
Commit 98780c48 authored by Davis, Duane T's avatar Davis, Duane T
Browse files

PATH_PLANNING: Added a plugin behavior template

plugin_behavior_template.py contains a template that can be used
by developers to implement new plugin behaviors.
parent 82016f67
No related branches found
No related tags found
No related merge requests found
#!/usr/bin/env python
#------------------------------------------------------------------------
# plugin_behavior_template.py
# Duane Davis, 2018
#
# Provides a template for the implementation of plugin swarm behaviors
# and instructions on what is required for each function. Behavior
# implementers can use this template by fully defining the PluginBehavior
# virtual methods as described below (additional methods can be defined,
# but the virtual methods below provide for full functionality within the
# current ACS swarm architecture.
#------------------------------------------------------------------------
# ACS imports
import ap_lib.plugin_behavior as plugin
import ap_lib.bitmapped_bytes as bytes
# import additional required ACS packages here:
# math or gps utilities, path planners, distributed algorithms, etc.
class NewPluginBehavior(plugin.PluginBehavior):
''' Class template inheriting from the PluginBehavior class
These behaviors are loaded into the swarm_manager node as a plugin and
are maintained as sub-objects within the containing SwarmManager object.
A reference is maintained in the behavior to the containing SwarmManager
object (self.manager). Rather than requiring each behavior to maintain
everything it needs to run, the containing SwarmManager object maintains
most information commonly required by behaviors and provides access to
contained behaviors through public variables and methods.
The following public variables are maintained in self.manager:
own_id: integer identification of the aircraft being controlled
ac_type: identifies the type of aircraft being controlled
swarm: dictionary of state records for all friendly swarm UAVs
swarm_update_time: time of most recent update to the swarm UAV states
swarm_keys: key values (IDs) of friendly swarm UAVs
subswarm_keys: key values (IDs) of UAVs assigned to the same subswarm
crashed_keys: key values (IDs) of friendly UAVs suspected of crashing
reds: dictionary of state records for all opposing swarm UAVs
reds_keys: key values (IDs) of opposing swarm UAVs
killed: list of all UAV IDs (friendly & opposing) IDed as "killed"
attacking: list of UAV IDs (friendly & opposing) IDed as on an "attack" run
ap_status_time: most recent receipt time of an autopilot status update
ap_mode: current autopilot mode
ap_wpt_id: current waypoint number in use by the autopilot
ap_wpt: current waypoint object in use by the autopilot
ap_wpt_types: dictionary of waypoint types containedin the mission file
last_wp: object containing the last waypoint in the mission file
locks: dictionary of thread safety RLock objects; the following are loaded:
SwarmManager.BEHAVIORS
SwarmManager.SWARM
SwarmManager.REDS
SwarmManager.KILLED
SwarmManager.ATTACKERS
SwarmManager.WAYPOINTS
wp_getlast_proxy: ROS service proxy for the wp_getlast service
wp_getrange_proxy: ROS service proxy for the wp_getrange service
wp_id_msg: container for publication to the waypoint_goto topic
wp_cmd_msg: container for publication to the payload_waypoint topic
spd_wp_cmd_msg: container for publication to the payload_speed_waypoint topic
rate_cmd_msg: container for publication to the payload_rate topic
behavior_data_publisher: ROS publisher to the send_swarm_behavior_data topic
behavior_data_msg: container object for publication to the send_swarm_behavior_data topic
behavior_data_to_publisher: ROS publisher to the send_swarm_behavior_data_to topic
directed_behavior_data_msg: container object for publication to the send_swarm_behavior_data_to topic
attack_report_publisher: ROS publisher to the attack_reports topic
attack_report_msg: container object for publication to the attack_reports topic
firing_report_publisher: ROS publisher to the firing_reports topic
firing_report_msg: container object for publication to the firing_reports topic
The following public methods are provided by self.manager:
get_subswarm: returns a dict of records of all subswarm aircraft
get_subswarm_id: returns the ID of the aircraft's current subswarm
get_swarm_state: returns the current swarm state of the aircraft
get_swarm_behavior: returns the currently active swarm behavior
release_stores: initiates release of one expendable store (if available)
Inherited class member variables (from PluginBehavior):
id: Unique integer identifier for this behavior
manager: BehaviorManager object to which this behavior belongs
Inherited class methods (from PluginBehavior):
set_manager: sets the manager object for this object
get_name: returns the string name of the behavior
set_ready: safely sets the ready state to True or False
is_ready: returns the behavior's current readiness state
set_active: safely activates or deactivates the behavior
is_active: returns the behavior's current active state
activation_time: returns time at which the behavior was activated
time_since_activation: returns elapsed time since activation
get_status: returns the behavior's current ready and active status
Virtual methods for implementation by the inheriting behavior
parameterize: parameterizes the behavior in preparation for activation
compute_command: runs one iteration of the behavior's control loop
safety_checks: runs required checks for continued safe execution
process_behavior_data: process SwarmBehaviorData messages
process_own_hit: perform any required "cleanup" when this UAV is hit
'''
def __init__(self, behavior_id, behavior_name, manager=None):
''' Class initializer sets base class member variables
Define and initialize any behavior-specific member variables here
@param behavior_id: unique identifier for this behavior
@param behavior_name: string name for this behavior
@param manager: BehaviorManager object to which this behavior belongs
'''
plugin.PluginBehavior.__init__(self, behavior_id, behavior_name, manager)
# Initialize any other behavior-specific variables
#------------------------------------------------------------------------
# PluginBehavior virtual methods implemented by inheriting behavior class
# Methods that are not required by the inheriting behavior can be removed
# (the stub method contained in the base class will suffice)
#------------------------------------------------------------------------
def parameterize(self, params):
''' Sets behavior parameters based on provided parameters
@param params: bitmapped byte array of behavior-specific parameters
@return True if set with valid parameters
The parameterize method parses the customized params byte array and
uses the parsed values to set the behavior-specific class variables.
An object inheriting from bytes.BitmappedBytes is used to parse the
array (a number of classes already exist, but behavior implementations
may require new ones to be defined). Parsed values should be tested
for validity as well.
'''
valid_params = True
# msg_parser = bytes.BitmappedBytes() (use appropriate parser type)
# msg_parser.unpack(params)
# set behavior member variables using msg_parser values
# compute/initialize additional member variable values as required
# set valid_params based on the validity of the parsed parameters
self.set_ready(valid_params)
self.manager.log_info("initializing NEW BEHAVIOR: %s"%valid_params)
return valid_params
def compute_command(self):
''' Runs one iteration of the behavior's control loop
Determine what control is required to realize the desired behavior
functionality and use the computed values to set one of the command
objects provided by the containing SwarmManager object. The type of
control required will dictate which object is used. Most behaviors
effect control by computing a waypoint that the vehicle will maneuver
towards, but rate, and waypoint-ID can also be commanded (see below)
@return waypoint (LLA), speed waypoint (LLAS), rate (YPS), or waypoint_id (Uint16)
'''
# Update the "state" of the behavior or make computations as required
# Use the computations to update one of the command values:
# self.manager.wp_cmd_msg (LLA) to drive towards a waypoint
# self.manager.spd_wp_cmd_msg (LLAS) to drive towards a waypoint with a new speed
# self.manager.rate_cmd_msg to (YPS) to control turn rate & forward speed
# self.manager.wp_id_msg (UInt16) to shift to a specific mission waypoint
return None # Change "None" to the updated command object
def safety_checks(self):
''' Conducts behavior-specific safety checks
Behavior checks should test all conditions upon which safe behavior
execution relies. Possible examples include timeliness of state data
from other swarm UAVs, lost contact with other UAVs in a formation,
using the incorrect mission waypoint ID, etc.
@return True if the behavior passes all safety checks (False otherwise)
'''
is_safe = True
# Conduct required checks and set is_safe to False if any fail
return is_safe
def process_behavior_data(self, data_msg):
''' Processes vehicle-to-vehicle SwarmBehaviorData messages
Behaviors that require inter-vehicle communications (network messages)
process received messages here. A message will be passed into the
function as an ap_msgs.SwarmBehaviorData object (data_msg parameter).
The data_msg.id field holds an enumeration indicating the type of
information that the message contains. The information itself is
contained in a bitmapped byte array (data_msg.params) that must be
parsed using a parser object inheriting from ap_lib.BitmappedBytes
(this may require definition of new parser objects). If multiple
types of data are required, this method can be implemented using a
series of if-elif blocks based on the data_msg.id value. Each block
is implemented similarly along the lines of the pattern below.
@param data_msg: ap_msgs.SwarmBehaviorData object with message data
'''
# if data_msg.id == bytes.MSG_TYPE1: (use appropriate message type)
# parser = bytes.BitmappedBytes() (use appropriate parser type)
# parser.unpack(data_msg.params)
# Process parsed message data as required
# elif data_msg.id == bytes.MSG_TYPE2: (use appropriate message type)
# parser = bytes.BitmappedBytes() (use appropriate parser type)
# parser.unpack(data_msg.params)
# Process parsed message data as required
# etc.
pass
def process_own_hit(self):
''' Perform any "cleanup" required when this UAV is hit
This method is only required for behaviors utilized during adversarial
game play (i.e., swarm versus swarm). Any actions that are required
to cleanly remove the vehicle from the game if it is "killed" should
be implemented here (e.g., disengage from a pursued target).
'''
pass
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment