Classes | Public Member Functions | Private Member Functions | Private Attributes
CrazyflieROS Class Reference

List of all members.

Classes

struct  log2
struct  logImu

Public Member Functions

 CrazyflieROS (const std::string &link_uri, const std::string &tf_prefix, float roll_trim, float pitch_trim, bool enable_logging, bool enable_parameters, std::vector< crazyflie_driver::LogBlock > &log_blocks, bool use_ros_time, bool enable_logging_imu, bool enable_logging_temperature, bool enable_logging_magnetic_field, bool enable_logging_pressure, bool enable_logging_battery, bool enable_logging_packets)
bool sendPacket (crazyflie_driver::sendPacket::Request &req, crazyflie_driver::sendPacket::Response &res)
void stop ()

Private Member Functions

struct CrazyflieROS::logImu __attribute__ ((packed))
struct CrazyflieROS::log2 __attribute__ ((packed))
void cmdVelChanged (const geometry_msgs::Twist::ConstPtr &msg)
bool emergency (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
void onEmptyAck (const crtpPlatformRSSIAck *data)
void onImuData (uint32_t time_in_ms, logImu *data)
void onLinkQuality (float linkQuality)
void onLog2Data (uint32_t time_in_ms, log2 *data)
void onLogCustom (uint32_t time_in_ms, std::vector< double > *values, void *userData)
void positionMeasurementChanged (const geometry_msgs::PointStamped::ConstPtr &msg)
void publishPackets ()
void run ()
template<class T , class U >
void updateParam (uint8_t id, const std::string &ros_param)
bool updateParams (crazyflie_driver::UpdateParams::Request &req, crazyflie_driver::UpdateParams::Response &res)

Private Attributes

Crazyflie m_cf
bool m_enable_logging_battery
bool m_enable_logging_imu
bool m_enable_logging_magnetic_field
bool m_enable_logging_packets
bool m_enable_logging_pressure
bool m_enable_logging_temperature
bool m_enableLogging
bool m_enableParameters
bool m_isEmergency
std::vector
< crazyflie_driver::LogBlock > 
m_logBlocks
float m_pitch_trim
ros::Publisher m_pubBattery
ros::Publisher m_pubImu
std::vector< ros::Publisherm_pubLogDataGeneric
ros::Publisher m_pubMag
ros::Publisher m_pubPackets
ros::Publisher m_pubPressure
ros::Publisher m_pubRssi
ros::Publisher m_pubTemp
float m_roll_trim
ros::ServiceServer m_sendPacketServer
bool m_sentExternalPosition
bool m_sentSetpoint
ros::ServiceServer m_serviceEmergency
ros::ServiceServer m_serviceUpdateParams
ros::Subscriber m_subscribeCmdVel
ros::Subscriber m_subscribeExternalPosition
std::string m_tf_prefix
std::thread m_thread
bool m_use_ros_time

Detailed Description

Definition at line 38 of file crazyflie_server.cpp.


Constructor & Destructor Documentation

CrazyflieROS::CrazyflieROS ( const std::string &  link_uri,
const std::string &  tf_prefix,
float  roll_trim,
float  pitch_trim,
bool  enable_logging,
bool  enable_parameters,
std::vector< crazyflie_driver::LogBlock > &  log_blocks,
bool  use_ros_time,
bool  enable_logging_imu,
bool  enable_logging_temperature,
bool  enable_logging_magnetic_field,
bool  enable_logging_pressure,
bool  enable_logging_battery,
bool  enable_logging_packets 
) [inline]

Definition at line 41 of file crazyflie_server.cpp.


Member Function Documentation

struct CrazyflieROS::logImu CrazyflieROS::__attribute__ ( (packed)  ) [private]
struct CrazyflieROS::log2 CrazyflieROS::__attribute__ ( (packed)  ) [private]
void CrazyflieROS::cmdVelChanged ( const geometry_msgs::Twist::ConstPtr &  msg) [inline, private]

Definition at line 255 of file crazyflie_server.cpp.

bool CrazyflieROS::emergency ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response res 
) [inline, private]

Definition at line 193 of file crazyflie_server.cpp.

void CrazyflieROS::onEmptyAck ( const crtpPlatformRSSIAck data) [inline, private]

Definition at line 511 of file crazyflie_server.cpp.

void CrazyflieROS::onImuData ( uint32_t  time_in_ms,
logImu data 
) [inline, private]

Definition at line 424 of file crazyflie_server.cpp.

void CrazyflieROS::onLinkQuality ( float  linkQuality) [inline, private]

Definition at line 518 of file crazyflie_server.cpp.

void CrazyflieROS::onLog2Data ( uint32_t  time_in_ms,
log2 data 
) [inline, private]

Definition at line 449 of file crazyflie_server.cpp.

void CrazyflieROS::onLogCustom ( uint32_t  time_in_ms,
std::vector< double > *  values,
void *  userData 
) [inline, private]

Definition at line 495 of file crazyflie_server.cpp.

void CrazyflieROS::positionMeasurementChanged ( const geometry_msgs::PointStamped::ConstPtr &  msg) [inline, private]

Definition at line 269 of file crazyflie_server.cpp.

void CrazyflieROS::publishPackets ( ) [inline, private]

Publishes any generic packets en-queued by the crazyflie to a crtpPacket topic.

Definition at line 154 of file crazyflie_server.cpp.

void CrazyflieROS::run ( ) [inline, private]

Definition at line 276 of file crazyflie_server.cpp.

bool CrazyflieROS::sendPacket ( crazyflie_driver::sendPacket::Request &  req,
crazyflie_driver::sendPacket::Response res 
) [inline]

Service callback which transmits a packet to the crazyflie

Parameters:
reqThe service request, which contains a crtpPacket to transmit.
resThe service response, which is not used.
Returns:
returns true always

Convert the message struct to the packet struct

Definition at line 132 of file crazyflie_server.cpp.

void CrazyflieROS::stop ( ) [inline]

Definition at line 119 of file crazyflie_server.cpp.

template<class T , class U >
void CrazyflieROS::updateParam ( uint8_t  id,
const std::string &  ros_param 
) [inline, private]

Definition at line 204 of file crazyflie_server.cpp.

bool CrazyflieROS::updateParams ( crazyflie_driver::UpdateParams::Request &  req,
crazyflie_driver::UpdateParams::Response res 
) [inline, private]

Definition at line 210 of file crazyflie_server.cpp.


Member Data Documentation

Definition at line 525 of file crazyflie_server.cpp.

Definition at line 538 of file crazyflie_server.cpp.

Definition at line 534 of file crazyflie_server.cpp.

Definition at line 536 of file crazyflie_server.cpp.

Definition at line 539 of file crazyflie_server.cpp.

Definition at line 537 of file crazyflie_server.cpp.

Definition at line 535 of file crazyflie_server.cpp.

Definition at line 530 of file crazyflie_server.cpp.

Definition at line 531 of file crazyflie_server.cpp.

Definition at line 527 of file crazyflie_server.cpp.

std::vector<crazyflie_driver::LogBlock> CrazyflieROS::m_logBlocks [private]

Definition at line 532 of file crazyflie_server.cpp.

float CrazyflieROS::m_pitch_trim [private]

Definition at line 529 of file crazyflie_server.cpp.

Definition at line 549 of file crazyflie_server.cpp.

Definition at line 545 of file crazyflie_server.cpp.

Definition at line 552 of file crazyflie_server.cpp.

Definition at line 547 of file crazyflie_server.cpp.

Definition at line 550 of file crazyflie_server.cpp.

Definition at line 548 of file crazyflie_server.cpp.

Definition at line 551 of file crazyflie_server.cpp.

Definition at line 546 of file crazyflie_server.cpp.

float CrazyflieROS::m_roll_trim [private]

Definition at line 528 of file crazyflie_server.cpp.

Definition at line 148 of file crazyflie_server.cpp.

Definition at line 554 of file crazyflie_server.cpp.

Definition at line 554 of file crazyflie_server.cpp.

Definition at line 541 of file crazyflie_server.cpp.

Definition at line 542 of file crazyflie_server.cpp.

Definition at line 543 of file crazyflie_server.cpp.

Definition at line 544 of file crazyflie_server.cpp.

std::string CrazyflieROS::m_tf_prefix [private]

Definition at line 526 of file crazyflie_server.cpp.

std::thread CrazyflieROS::m_thread [private]

Definition at line 556 of file crazyflie_server.cpp.

Definition at line 533 of file crazyflie_server.cpp.


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


crazyflie_driver
Author(s): Wolfgang Hoenig
autogenerated on Sun Oct 8 2017 02:48:03