ASCO Aerial Autonomy
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
test_utils::BaseTestPubSubs Struct Reference

Base Test fixture class for reducing code redundancy in system handler tests. More...

#include <test_utils.h>

Public Member Functions

 BaseTestPubSubs ()
 Constructor. More...
 
void publishEvent (std::string event)
 Helper function to publish specified event specified. More...
 
void publishPoseCommand (PositionYaw position_yaw)
 Helper function to publish specified position_yaw command. More...
 
PositionYaw getPositionYaw (parsernode::common::quaddata quad_data)
 Helper function to return position and yaw from UAV data. More...
 
bool isStatusConnected ()
 Helper function to check if status subscriber to connected UAV status publisher. More...
 

Protected Member Functions

void statusCallback (std_msgs::String status)
 Callback to set the status received from UAV. More...
 

Protected Attributes

std::string status_
 
ros::NodeHandle nh_send_
 Send events. More...
 
ros::NodeHandle nh_receive_status_
 Receive status. More...
 
ros::Publisher event_pub_
 Event publisher. More...
 
ros::Publisher pose_pub_
 Pose command publisher. More...
 
ros::Subscriber status_subscriber_
 System status subscriber. More...
 

Detailed Description

Base Test fixture class for reducing code redundancy in system handler tests.

Constructor & Destructor Documentation

test_utils::BaseTestPubSubs::BaseTestPubSubs ( )
inline

Constructor.

Initializes event, pose publishers, and system status subscriber

Member Function Documentation

PositionYaw test_utils::BaseTestPubSubs::getPositionYaw ( parsernode::common::quaddata  quad_data)
inline

Helper function to return position and yaw from UAV data.

Parameters
quad_dataUAV data returned by uav system
Returns
Position and yaw of UAV
bool test_utils::BaseTestPubSubs::isStatusConnected ( )
inline

Helper function to check if status subscriber to connected UAV status publisher.

Returns
true if connected
void test_utils::BaseTestPubSubs::publishEvent ( std::string  event)
inline

Helper function to publish specified event specified.

Parameters
eventEvent to publish
void test_utils::BaseTestPubSubs::publishPoseCommand ( PositionYaw  position_yaw)
inline

Helper function to publish specified position_yaw command.

Parameters
position_yawposition and yaw to publish
void test_utils::BaseTestPubSubs::statusCallback ( std_msgs::String  status)
inlineprotected

Callback to set the status received from UAV.

Parameters
statusText status received from UAV

Member Data Documentation

ros::Publisher test_utils::BaseTestPubSubs::event_pub_
protected

Event publisher.

ros::NodeHandle test_utils::BaseTestPubSubs::nh_receive_status_
protected

Receive status.

ros::NodeHandle test_utils::BaseTestPubSubs::nh_send_
protected

Send events.

ros::Publisher test_utils::BaseTestPubSubs::pose_pub_
protected

Pose command publisher.

std::string test_utils::BaseTestPubSubs::status_
protected
ros::Subscriber test_utils::BaseTestPubSubs::status_subscriber_
protected

System status subscriber.


The documentation for this struct was generated from the following file: