Classes | Namespaces | Enumerations | Enumerator | Functions | Variables
Sitl_test

SITL test node implementation. More...

Classes

class  testsetup::OffboardControl
class  sitltest::SitlTest
 SITL test node class. More...
class  testsetup::TestSetup

Namespaces

namespace  sitltest
namespace  testsetup

Enumerations

enum  testsetup::control_mode { testsetup::POSITION, testsetup::VELOCITY, testsetup::ACCELERATION }
 Offboard controller tester. More...
enum  testsetup::path_shape { testsetup::SQUARE, testsetup::CIRCLE, testsetup::EIGHT, testsetup::ELLIPSE }

Functions

void testsetup::OffboardControl::circle_path_motion (ros::Rate loop_rate, control_mode mode)
 Circle path motion routine.
Eigen::Vector3d testsetup::OffboardControl::circle_shape (int angle)
 Defines circle path.
void testsetup::OffboardControl::eight_path_motion (ros::Rate loop_rate, control_mode mode)
 Eight path motion routine.
Eigen::Vector3d testsetup::OffboardControl::eight_shape (int angle)
 Defines Gerono lemniscate path.
void testsetup::OffboardControl::ellipse_path_motion (ros::Rate loop_rate, control_mode mode)
 Ellipse path motion routine.
Eigen::Vector3d testsetup::OffboardControl::ellipse_shape (int angle)
 Defines ellipse path.
void testsetup::OffboardControl::init ()
void testsetup::OffboardControl::local_pos_cb (const geometry_msgs::PoseStampedConstPtr &msg)
 testsetup::OffboardControl::OffboardControl ()
Eigen::Vector3d testsetup::OffboardControl::pos_setpoint (int tr_x, int tr_y, int tr_z)
 Defines single position setpoint.
void testsetup::TestSetup::setup (const ros::NodeHandle &nh)
 sitltest::SitlTest::SitlTest ()
static void sitltest::SitlTest::spin (int argc, char *argv[])
void testsetup::OffboardControl::spin (int argc, char *argv[])
void testsetup::OffboardControl::square_path_motion (ros::Rate loop_rate, control_mode mode)
 Square path motion routine.
 testsetup::TestSetup::TestSetup ()
std::array< double, 100 > testsetup::OffboardControl::threshold_definition ()
 Gaussian noise generator for accepted position threshold.
void testsetup::OffboardControl::wait_and_move (geometry_msgs::PoseStamped target)
 Defines the accepted threshold to the destination/target position before moving to the next setpoint.
 sitltest::SitlTest::~SitlTest ()
 testsetup::TestSetup::~TestSetup ()

Variables

Eigen::Vector3d testsetup::OffboardControl::current
double testsetup::OffboardControl::linvel_d_gain
double testsetup::OffboardControl::linvel_i_gain
double testsetup::OffboardControl::linvel_i_max
double testsetup::OffboardControl::linvel_i_min
double testsetup::OffboardControl::linvel_p_gain
ros::Publisher testsetup::OffboardControl::local_pos_sp_pub
ros::Subscriber testsetup::OffboardControl::local_pos_sub
geometry_msgs::PoseStamped testsetup::OffboardControl::localpos
control_mode testsetup::OffboardControl::mode
ros::NodeHandle testsetup::TestSetup::nh
ros::NodeHandle testsetup::OffboardControl::nh_sp
int testsetup::TestSetup::num_of_tests
int testsetup::OffboardControl::num_of_tests
pidcontroller::PIDController testsetup::OffboardControl::pid
geometry_msgs::PoseStamped testsetup::OffboardControl::ps
double testsetup::TestSetup::rate
double testsetup::OffboardControl::rate
path_shape testsetup::OffboardControl::shape
TestSetup testsetup::OffboardControl::test
std::array< double, 100 > testsetup::OffboardControl::threshold
bool testsetup::TestSetup::use_pid
bool testsetup::OffboardControl::use_pid
ros::Publisher testsetup::OffboardControl::vel_sp_pub
geometry_msgs::TwistStamped testsetup::OffboardControl::vs
double testsetup::OffboardControl::yawrate_d_gain
double testsetup::OffboardControl::yawrate_i_gain
double testsetup::OffboardControl::yawrate_i_max
double testsetup::OffboardControl::yawrate_i_min
double testsetup::OffboardControl::yawrate_p_gain

Detailed Description

SITL test node implementation.

SITL tests setup.


Enumeration Type Documentation

Offboard controller tester.

Tests offboard position, velocity and acceleration control

Enumerator:
POSITION 
VELOCITY 
ACCELERATION 

Definition at line 36 of file offboard_control.h.

Enumerator:
SQUARE 
CIRCLE 
EIGHT 
ELLIPSE 

Definition at line 42 of file offboard_control.h.


Function Documentation

void testsetup::OffboardControl::circle_path_motion ( ros::Rate  loop_rate,
control_mode  mode 
) [inline, private]

Circle path motion routine.

Definition at line 312 of file offboard_control.h.

Eigen::Vector3d testsetup::OffboardControl::circle_shape ( int  angle) [inline, private]

Defines circle path.

Todo:
Give possibility to user define amplitude of movement (circle radius)

Definition at line 230 of file offboard_control.h.

void testsetup::OffboardControl::eight_path_motion ( ros::Rate  loop_rate,
control_mode  mode 
) [inline, private]

Eight path motion routine.

Definition at line 372 of file offboard_control.h.

Eigen::Vector3d testsetup::OffboardControl::eight_shape ( int  angle) [inline, private]

Defines Gerono lemniscate path.

Todo:
Give possibility to user define amplitude of movement (vertical tangent size)

Definition at line 242 of file offboard_control.h.

void testsetup::OffboardControl::ellipse_path_motion ( ros::Rate  loop_rate,
control_mode  mode 
) [inline, private]

Ellipse path motion routine.

Definition at line 432 of file offboard_control.h.

Eigen::Vector3d testsetup::OffboardControl::ellipse_shape ( int  angle) [inline, private]

Defines ellipse path.

Todo:
Give possibility to user define amplitude of movement (tangent sizes)

Definition at line 254 of file offboard_control.h.

Setup of the test conditions

Note:
some of these are based on values defaulted @ https://bitbucket.org/enddl22/ardrone_side_project/ tweaks to them so to get a better velocity response are welcomed!

Setpoint control mode selector

Available modes:

  • position
  • velocity
  • acceleration

Setpoint path shape selector

Available shapes:

  • square
  • circle
  • eight
  • ellipse (in 3D space)

Definition at line 59 of file offboard_control.h.

void testsetup::OffboardControl::local_pos_cb ( const geometry_msgs::PoseStampedConstPtr &  msg) [inline, private]

Definition at line 554 of file offboard_control.h.

Definition at line 51 of file offboard_control.h.

Eigen::Vector3d testsetup::OffboardControl::pos_setpoint ( int  tr_x,
int  tr_y,
int  tr_z 
) [inline, private]

Defines single position setpoint.

Todo:
Give possibility to user define amplitude of movement (square corners coordinates)

Definition at line 222 of file offboard_control.h.

void testsetup::TestSetup::setup ( const ros::NodeHandle nh) [inline]

Definition at line 36 of file test_setup.h.

SitlTest::SitlTest ( )

Definition at line 20 of file sitl_test.cpp.

void SitlTest::spin ( int  argc,
char *  argv[] 
) [static]
Todo:
add more testing structures

Definition at line 23 of file sitl_test.cpp.

void testsetup::OffboardControl::spin ( int  argc,
char *  argv[] 
) [inline]
Todo:
: lacks firmware support, for now

Definition at line 143 of file offboard_control.h.

void testsetup::OffboardControl::square_path_motion ( ros::Rate  loop_rate,
control_mode  mode 
) [inline, private]

Square path motion routine.

Definition at line 268 of file offboard_control.h.

Definition at line 25 of file test_setup.h.

std::array<double, 100> testsetup::OffboardControl::threshold_definition ( ) [inline, private]

Gaussian noise generator for accepted position threshold.

Definition at line 539 of file offboard_control.h.

void testsetup::OffboardControl::wait_and_move ( geometry_msgs::PoseStamped  target) [inline, private]

Defines the accepted threshold to the destination/target position before moving to the next setpoint.

Definition at line 493 of file offboard_control.h.

Definition at line 34 of file sitl_test.h.

Definition at line 28 of file test_setup.h.


Variable Documentation

Eigen::Vector3d testsetup::OffboardControl::current [private]

Definition at line 213 of file offboard_control.h.

Definition at line 192 of file offboard_control.h.

Definition at line 191 of file offboard_control.h.

Definition at line 193 of file offboard_control.h.

Definition at line 194 of file offboard_control.h.

Definition at line 190 of file offboard_control.h.

Definition at line 206 of file offboard_control.h.

Definition at line 208 of file offboard_control.h.

geometry_msgs::PoseStamped testsetup::OffboardControl::localpos [private]

Definition at line 210 of file offboard_control.h.

control_mode testsetup::OffboardControl::mode [private]

Definition at line 202 of file offboard_control.h.

Definition at line 28 of file test_setup.h.

Definition at line 205 of file offboard_control.h.

Definition at line 34 of file test_setup.h.

Definition at line 188 of file offboard_control.h.

Definition at line 184 of file offboard_control.h.

geometry_msgs::PoseStamped testsetup::OffboardControl::ps [private]

Definition at line 210 of file offboard_control.h.

Definition at line 33 of file test_setup.h.

Definition at line 186 of file offboard_control.h.

path_shape testsetup::OffboardControl::shape [private]

Definition at line 203 of file offboard_control.h.

TestSetup testsetup::OffboardControl::test [private]

Definition at line 183 of file offboard_control.h.

std::array<double, 100> testsetup::OffboardControl::threshold [private]

Definition at line 215 of file offboard_control.h.

Definition at line 32 of file test_setup.h.

Definition at line 187 of file offboard_control.h.

Definition at line 207 of file offboard_control.h.

geometry_msgs::TwistStamped testsetup::OffboardControl::vs [private]

Definition at line 211 of file offboard_control.h.

Definition at line 198 of file offboard_control.h.

Definition at line 197 of file offboard_control.h.

Definition at line 199 of file offboard_control.h.

Definition at line 200 of file offboard_control.h.

Definition at line 196 of file offboard_control.h.



test_mavros
Author(s): Nuno Marques , Vladimir Ermakov
autogenerated on Sat Jun 8 2019 19:55:31