Public Member Functions | Private Member Functions | Private Attributes | Static 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 controlCmdCallbackMavComm (const mav_msgs::RollPitchYawrateThrustConstPtr &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_mav_comm_sub_
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_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_
std::string mav_type_
ros::ServiceServer motor_srv_
ros::Publisher motors_pub_
 publisher for motor message
ros::NodeHandle nh_
ros::NodeHandle pnh_
ros::Publisher pressure_height_pub_
ros::Publisher rc_joy_pub_
ros::Publisher rc_pub_
ReconfigureServerreconf_srv_
asctec_hl_comm::mav_status status_
ros::Publisher status_pub_

Static Private Attributes

static const double kDefaultMaxRCChannelValue = 4080

Detailed Description

Definition at line 72 of file hl_interface.h.


Constructor & Destructor Documentation

Definition at line 36 of file hl_interface.cpp.

Definition at line 89 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 792 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 551 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 459 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 511 of file hl_interface.cpp.

void HLInterface::controlCmdCallbackMavComm ( const mav_msgs::RollPitchYawrateThrustConstPtr &  msg) [private]

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

Definition at line 517 of file hl_interface.cpp.

Definition at line 389 of file hl_interface.cpp.

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

Definition at line 155 of file hl_interface.cpp.

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

Definition at line 94 of file hl_interface.cpp.

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

Definition at line 441 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 214 of file hl_interface.cpp.

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

Definition at line 269 of file hl_interface.cpp.

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

Definition at line 429 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 651 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 557 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 744 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 715 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 693 of file hl_interface.cpp.


Member Data Documentation

Definition at line 147 of file hl_interface.h.

Definition at line 78 of file hl_interface.h.

asctec_hl_interface::HLInterfaceConfig HLInterface::config_ [private]

Definition at line 172 of file hl_interface.h.

Definition at line 93 of file hl_interface.h.

Definition at line 92 of file hl_interface.h.

Definition at line 97 of file hl_interface.h.

Definition at line 176 of file hl_interface.h.

Definition at line 178 of file hl_interface.h.

Definition at line 177 of file hl_interface.h.

Definition at line 175 of file hl_interface.h.

short HLInterface::enable_ctrl_ [private]

stores the bitmask of degrees of freedom to be controlled

Definition at line 152 of file hl_interface.h.

std::string HLInterface::frame_id_ [private]

Definition at line 80 of file hl_interface.h.

Definition at line 84 of file hl_interface.h.

Definition at line 83 of file hl_interface.h.

Definition at line 145 of file hl_interface.h.

int16_t HLInterface::gps_status_ [private]

Definition at line 144 of file hl_interface.h.

publisher for sensor_msgs/Imu message

Definition at line 85 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 159 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 166 of file hl_interface.h.

const double HLInterface::kDefaultMaxRCChannelValue = 4080 [static, private]

Definition at line 99 of file hl_interface.h.

Definition at line 148 of file hl_interface.h.

Definition at line 91 of file hl_interface.h.

std::string HLInterface::mav_type_ [private]

Definition at line 81 of file hl_interface.h.

Definition at line 96 of file hl_interface.h.

publisher for motor message

Definition at line 86 of file hl_interface.h.

Definition at line 76 of file hl_interface.h.

Definition at line 77 of file hl_interface.h.

Definition at line 87 of file hl_interface.h.

Definition at line 89 of file hl_interface.h.

Definition at line 88 of file hl_interface.h.

Definition at line 170 of file hl_interface.h.

asctec_hl_comm::mav_status HLInterface::status_ [private]

Definition at line 149 of file hl_interface.h.

Definition at line 90 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 Jun 6 2019 20:57:17