Public Member Functions | Private Member Functions | Private Attributes
HLInterface Class Reference

#include <hl_interface.h>

List of all members.

Public Member Functions

 HLInterface (ros::NodeHandle &nh, CommPtr &comm)
 ~HLInterface ()

Private Member Functions

void cbConfig (asctec_hl_interface::HLInterfaceConfig &config, uint32_t level)
bool cbCtrl (asctec_hl_comm::MavCtrlSrv::Request &req, asctec_hl_comm::MavCtrlSrv::Response &resp)
 ctrl service callback
bool cbMotors (asctec_hl_comm::mav_ctrl_motors::Request &req, asctec_hl_comm::mav_ctrl_motors::Response &resp)
 service to start/stop motors
void controlCmdCallback (const asctec_hl_comm::mav_ctrlConstPtr &msg)
void diagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)
void processGpsData (uint8_t *buf, uint32_t bufLength)
void processImuData (uint8_t *buf, uint32_t bufLength)
void processMagData (uint8_t *buf, uint32_t bufLength)
void processPoseEKFData (uint8_t *buf, uint32_t bufLength)
void processRcData (uint8_t *buf, uint32_t bufLength)
void processStatusData (uint8_t *buf, uint32_t bufLength)
void processTimeSyncData (uint8_t *buf, uint32_t bufLength)
void sendAccCommandLL (const asctec_hl_comm::mav_ctrl &ctrl, asctec_hl_comm::mav_ctrl *ctrl_result=NULL)
 sends an acceleration command (pitch, roll, thrust), yaw velocity to the LL processor
void sendControlCmd (const asctec_hl_comm::mav_ctrl &ctrl, asctec_hl_comm::mav_ctrl *ctrl_result=NULL)
 evaluates the mav_ctrl message and sends the appropriate commands to the HLP
void sendPosCommandHL (const asctec_hl_comm::mav_ctrl &ctrl, asctec_hl_comm::mav_ctrl *ctrl_result=NULL)
 sends a position (=waypoint) command to the HL. Position control on the HL has to be enabled
void sendVelCommandHL (const asctec_hl_comm::mav_ctrl &ctrl, asctec_hl_comm::mav_ctrl *ctrl_result=NULL)
 sends a velocity command to the LLP. Velocity is controlled based on GPS
void sendVelCommandLL (const asctec_hl_comm::mav_ctrl &ctrl, asctec_hl_comm::mav_ctrl *ctrl_result=NULL)
 sends a velocity command to the HLP. Position control on the HL has to be enabled

Private Attributes

double angular_velocity_variance_
CommPtrcomm_
asctec_hl_interface::HLInterfaceConfig config_
ros::Subscriber control_sub_
ros::ServiceServer crtl_srv_
diagnostic_updater::FrequencyStatus diag_imu_freq_
double diag_imu_freq_max_
double diag_imu_freq_min_
diagnostic_updater::Updater diag_updater_
short enable_ctrl_
 stores the bitmask of degrees of freedom to be controlled
std::string frame_id_
ros::Publisher gps_custom_pub_
ros::Publisher gps_pub_
int16_t gps_satellites_used_
int16_t gps_status_
ros::Publisher imu_pub_
 publisher for custom asctec_hl_comm/mav_imu message
ros::Publisher imu_ros_pub_
 publisher for sensor_msgs/Imu message
int k_stick_
 gain from AutoPilot values to 1/1000 degree for the input from the pitch and roll "stick"
int k_stick_yaw_
 gain from AutoPilot values to 1/1000 degree for the input from the yaw "stick"
double linear_acceleration_variance_
ros::Publisher mag_pub_
ros::ServiceServer motor_srv_
ros::Publisher motors_pub_
 publisher for motor message
ros::NodeHandle nh_
ros::NodeHandle pnh_
ros::Publisher rc_pub_
ReconfigureServerreconf_srv_
asctec_hl_comm::mav_status status_
ros::Publisher status_pub_

Detailed Description

Definition at line 67 of file hl_interface.h.


Constructor & Destructor Documentation

Definition at line 36 of file hl_interface.cpp.

Definition at line 84 of file hl_interface.cpp.


Member Function Documentation

void HLInterface::cbConfig ( asctec_hl_interface::HLInterfaceConfig &  config,
uint32_t  level 
) [private]

bits for the control byte: bit 0: pitch control enabled bit 1: roll control enabled bit 2: yaw control enabled bit 3: thrust control enabled bit 4: Height control enabled bit 5: GPS position control enabled

Definition at line 731 of file hl_interface.cpp.

bool HLInterface::cbCtrl ( asctec_hl_comm::MavCtrlSrv::Request &  req,
asctec_hl_comm::MavCtrlSrv::Response &  resp 
) [private]

ctrl service callback

Definition at line 490 of file hl_interface.cpp.

bool HLInterface::cbMotors ( asctec_hl_comm::mav_ctrl_motors::Request &  req,
asctec_hl_comm::mav_ctrl_motors::Response &  resp 
) [private]

service to start/stop motors

Definition at line 433 of file hl_interface.cpp.

void HLInterface::controlCmdCallback ( const asctec_hl_comm::mav_ctrlConstPtr &  msg) [private]

callback that listens to mav_ctrl messages message must be sent at least at 10 Hz, otherwise the mav will switch back to manual control!

Definition at line 485 of file hl_interface.cpp.

Definition at line 363 of file hl_interface.cpp.

void HLInterface::processGpsData ( uint8_t *  buf,
uint32_t  bufLength 
) [private]

Definition at line 165 of file hl_interface.cpp.

void HLInterface::processImuData ( uint8_t *  buf,
uint32_t  bufLength 
) [private]

Definition at line 89 of file hl_interface.cpp.

void HLInterface::processMagData ( uint8_t *  buf,
uint32_t  bufLength 
) [private]

Definition at line 415 of file hl_interface.cpp.

void HLInterface::processPoseEKFData ( uint8_t *  buf,
uint32_t  bufLength 
) [private]
void HLInterface::processRcData ( uint8_t *  buf,
uint32_t  bufLength 
) [private]

Definition at line 224 of file hl_interface.cpp.

void HLInterface::processStatusData ( uint8_t *  buf,
uint32_t  bufLength 
) [private]

Definition at line 243 of file hl_interface.cpp.

void HLInterface::processTimeSyncData ( uint8_t *  buf,
uint32_t  bufLength 
) [private]

Definition at line 403 of file hl_interface.cpp.

void HLInterface::sendAccCommandLL ( const asctec_hl_comm::mav_ctrl &  ctrl,
asctec_hl_comm::mav_ctrl *  ctrl_result = NULL 
) [private]

sends an acceleration command (pitch, roll, thrust), yaw velocity to the LL processor

Definition at line 590 of file hl_interface.cpp.

void HLInterface::sendControlCmd ( const asctec_hl_comm::mav_ctrl &  ctrl,
asctec_hl_comm::mav_ctrl *  ctrl_result = NULL 
) [private]

evaluates the mav_ctrl message and sends the appropriate commands to the HLP

Definition at line 496 of file hl_interface.cpp.

void HLInterface::sendPosCommandHL ( const asctec_hl_comm::mav_ctrl &  ctrl,
asctec_hl_comm::mav_ctrl *  ctrl_result = NULL 
) [private]

sends a position (=waypoint) command to the HL. Position control on the HL has to be enabled

Definition at line 683 of file hl_interface.cpp.

void HLInterface::sendVelCommandHL ( const asctec_hl_comm::mav_ctrl &  ctrl,
asctec_hl_comm::mav_ctrl *  ctrl_result = NULL 
) [private]

sends a velocity command to the LLP. Velocity is controlled based on GPS

Definition at line 654 of file hl_interface.cpp.

void HLInterface::sendVelCommandLL ( const asctec_hl_comm::mav_ctrl &  ctrl,
asctec_hl_comm::mav_ctrl *  ctrl_result = NULL 
) [private]

sends a velocity command to the HLP. Position control on the HL has to be enabled

Definition at line 632 of file hl_interface.cpp.


Member Data Documentation

Definition at line 129 of file hl_interface.h.

Definition at line 73 of file hl_interface.h.

asctec_hl_interface::HLInterfaceConfig HLInterface::config_ [private]

Definition at line 154 of file hl_interface.h.

Definition at line 85 of file hl_interface.h.

Definition at line 88 of file hl_interface.h.

Definition at line 158 of file hl_interface.h.

Definition at line 160 of file hl_interface.h.

Definition at line 159 of file hl_interface.h.

Definition at line 157 of file hl_interface.h.

short HLInterface::enable_ctrl_ [private]

stores the bitmask of degrees of freedom to be controlled

Definition at line 134 of file hl_interface.h.

std::string HLInterface::frame_id_ [private]

Definition at line 75 of file hl_interface.h.

Definition at line 78 of file hl_interface.h.

Definition at line 77 of file hl_interface.h.

Definition at line 127 of file hl_interface.h.

int16_t HLInterface::gps_status_ [private]

Definition at line 126 of file hl_interface.h.

publisher for custom asctec_hl_comm/mav_imu message

Definition at line 80 of file hl_interface.h.

publisher for sensor_msgs/Imu message

Definition at line 79 of file hl_interface.h.

int HLInterface::k_stick_ [private]

gain from AutoPilot values to 1/1000 degree for the input from the pitch and roll "stick"

This value should be equal to the one that can be found when reading the controller parameters of the LLP by the AscTec AutoPilot software. It is only relevant, when this interface is used to send roll/pitch (or x/y velocity when in GPS mode) commands to the LLP.

Definition at line 141 of file hl_interface.h.

gain from AutoPilot values to 1/1000 degree for the input from the yaw "stick"

This value should be equal to the one that can be found when reading the controller parameters of the LLP by the AscTec AutoPilot software. It is only relevant, when this interface is used to send yaw commands to the LLP.

Definition at line 148 of file hl_interface.h.

Definition at line 130 of file hl_interface.h.

Definition at line 84 of file hl_interface.h.

Definition at line 87 of file hl_interface.h.

publisher for motor message

Definition at line 81 of file hl_interface.h.

Definition at line 71 of file hl_interface.h.

Definition at line 72 of file hl_interface.h.

Definition at line 82 of file hl_interface.h.

Definition at line 152 of file hl_interface.h.

asctec_hl_comm::mav_status HLInterface::status_ [private]

Definition at line 131 of file hl_interface.h.

Definition at line 83 of file hl_interface.h.


The documentation for this class was generated from the following files:


asctec_hl_interface
Author(s): Markus Achtelik, Michael Achtelik, Stephan Weiss, Laurent Kneip
autogenerated on Thu Aug 27 2015 12:26:52