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

List of all members.

Classes

struct  log2
struct  logImu
struct  logPose

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_pose, 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))
struct CrazyflieROS::logPose __attribute__ ((packed))
void cmdFullStateSetpoint (const crazyflie_driver::FullState::ConstPtr &msg)
void cmdHoverSetpoint (const crazyflie_driver::Hover::ConstPtr &msg)
void cmdPositionSetpoint (const crazyflie_driver::Position::ConstPtr &msg)
void cmdStop (const std_msgs::Empty::ConstPtr &msg)
void cmdVelChanged (const geometry_msgs::Twist::ConstPtr &msg)
bool emergency (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
bool goTo (crazyflie_driver::GoTo::Request &req, crazyflie_driver::GoTo::Response &res)
bool land (crazyflie_driver::Land::Request &req, crazyflie_driver::Land::Response &res)
void onConsole (const char *msg)
void onEmptyAck (const crtpPlatformRSSIAck *data)
void onGenericPacket (const ITransport::Ack &ack)
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 onPoseData (uint32_t time_in_ms, logPose *data)
void poseMeasurementChanged (const geometry_msgs::PoseStamped::ConstPtr &msg)
void positionMeasurementChanged (const geometry_msgs::PointStamped::ConstPtr &msg)
void run ()
bool setGroupMask (crazyflie_driver::SetGroupMask::Request &req, crazyflie_driver::SetGroupMask::Response &res)
bool startTrajectory (crazyflie_driver::StartTrajectory::Request &req, crazyflie_driver::StartTrajectory::Response &res)
bool stop (crazyflie_driver::Stop::Request &req, crazyflie_driver::Stop::Response &res)
bool takeoff (crazyflie_driver::Takeoff::Request &req, crazyflie_driver::Takeoff::Response &res)
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)
bool uploadTrajectory (crazyflie_driver::UploadTrajectory::Request &req, crazyflie_driver::UploadTrajectory::Response &res)

Private Attributes

ros::CallbackQueue m_callback_queue
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_pose
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_pubPose
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_serviceGoTo
ros::ServiceServer m_serviceLand
ros::ServiceServer m_serviceSetGroupMask
ros::ServiceServer m_serviceStartTrajectory
ros::ServiceServer m_serviceStop
ros::ServiceServer m_serviceTakeoff
ros::ServiceServer m_serviceUpdateParams
ros::ServiceServer m_serviceUploadTrajectory
ros::Subscriber m_subscribeCmdFullState
ros::Subscriber m_subscribeCmdHover
ros::Subscriber m_subscribeCmdPosition
ros::Subscriber m_subscribeCmdStop
ros::Subscriber m_subscribeCmdVel
ros::Subscriber m_subscribeExternalPose
ros::Subscriber m_subscribeExternalPosition
std::string m_tf_prefix
std::thread m_thread
bool m_use_ros_time

Detailed Description

Definition at line 82 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_pose,
bool  enable_logging_packets 
) [inline]

Definition at line 85 of file crazyflie_server.cpp.


Member Function Documentation

struct CrazyflieROS::logImu CrazyflieROS::__attribute__ ( (packed)  ) [private]
struct CrazyflieROS::log2 CrazyflieROS::__attribute__ ( (packed)  ) [private]
struct CrazyflieROS::logPose CrazyflieROS::__attribute__ ( (packed)  ) [private]
void CrazyflieROS::cmdFullStateSetpoint ( const crazyflie_driver::FullState::ConstPtr &  msg) [inline, private]

Definition at line 320 of file crazyflie_server.cpp.

void CrazyflieROS::cmdHoverSetpoint ( const crazyflie_driver::Hover::ConstPtr &  msg) [inline, private]

Definition at line 220 of file crazyflie_server.cpp.

void CrazyflieROS::cmdPositionSetpoint ( const crazyflie_driver::Position::ConstPtr &  msg) [inline, private]

Definition at line 247 of file crazyflie_server.cpp.

void CrazyflieROS::cmdStop ( const std_msgs::Empty::ConstPtr &  msg) [inline, private]

Definition at line 236 of file crazyflie_server.cpp.

void CrazyflieROS::cmdVelChanged ( const geometry_msgs::Twist::ConstPtr &  msg) [inline, private]

Definition at line 306 of file crazyflie_server.cpp.

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

Definition at line 202 of file crazyflie_server.cpp.

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

Definition at line 765 of file crazyflie_server.cpp.

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

Definition at line 747 of file crazyflie_server.cpp.

void CrazyflieROS::onConsole ( const char *  msg) [inline, private]

Definition at line 710 of file crazyflie_server.cpp.

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

Definition at line 697 of file crazyflie_server.cpp.

void CrazyflieROS::onGenericPacket ( const ITransport::Ack ack) [inline, private]

Definition at line 721 of file crazyflie_server.cpp.

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

Definition at line 585 of file crazyflie_server.cpp.

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

Definition at line 704 of file crazyflie_server.cpp.

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

Definition at line 610 of file crazyflie_server.cpp.

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

Definition at line 681 of file crazyflie_server.cpp.

void CrazyflieROS::onPoseData ( uint32_t  time_in_ms,
logPose data 
) [inline, private]

Definition at line 656 of file crazyflie_server.cpp.

void CrazyflieROS::poseMeasurementChanged ( const geometry_msgs::PoseStamped::ConstPtr &  msg) [inline, private]

Definition at line 361 of file crazyflie_server.cpp.

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

Definition at line 354 of file crazyflie_server.cpp.

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

Definition at line 370 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 160 of file crazyflie_server.cpp.

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

Definition at line 729 of file crazyflie_server.cpp.

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

Definition at line 803 of file crazyflie_server.cpp.

void CrazyflieROS::stop ( ) [inline]

Definition at line 147 of file crazyflie_server.cpp.

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

Definition at line 756 of file crazyflie_server.cpp.

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

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

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

Definition at line 261 of file crazyflie_server.cpp.

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

Definition at line 774 of file crazyflie_server.cpp.


Member Data Documentation

Definition at line 863 of file crazyflie_server.cpp.

Definition at line 814 of file crazyflie_server.cpp.

Definition at line 826 of file crazyflie_server.cpp.

Definition at line 822 of file crazyflie_server.cpp.

Definition at line 824 of file crazyflie_server.cpp.

Definition at line 828 of file crazyflie_server.cpp.

Definition at line 827 of file crazyflie_server.cpp.

Definition at line 825 of file crazyflie_server.cpp.

Definition at line 823 of file crazyflie_server.cpp.

Definition at line 818 of file crazyflie_server.cpp.

Definition at line 819 of file crazyflie_server.cpp.

Definition at line 815 of file crazyflie_server.cpp.

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

Definition at line 820 of file crazyflie_server.cpp.

float CrazyflieROS::m_pitch_trim [private]

Definition at line 817 of file crazyflie_server.cpp.

Definition at line 854 of file crazyflie_server.cpp.

Definition at line 850 of file crazyflie_server.cpp.

Definition at line 858 of file crazyflie_server.cpp.

Definition at line 852 of file crazyflie_server.cpp.

Definition at line 856 of file crazyflie_server.cpp.

Definition at line 855 of file crazyflie_server.cpp.

Definition at line 853 of file crazyflie_server.cpp.

Definition at line 857 of file crazyflie_server.cpp.

Definition at line 851 of file crazyflie_server.cpp.

float CrazyflieROS::m_roll_trim [private]

Definition at line 816 of file crazyflie_server.cpp.

Definition at line 832 of file crazyflie_server.cpp.

Definition at line 860 of file crazyflie_server.cpp.

Definition at line 860 of file crazyflie_server.cpp.

Definition at line 830 of file crazyflie_server.cpp.

Definition at line 839 of file crazyflie_server.cpp.

Definition at line 837 of file crazyflie_server.cpp.

Definition at line 835 of file crazyflie_server.cpp.

Definition at line 841 of file crazyflie_server.cpp.

Definition at line 838 of file crazyflie_server.cpp.

Definition at line 836 of file crazyflie_server.cpp.

Definition at line 831 of file crazyflie_server.cpp.

Definition at line 840 of file crazyflie_server.cpp.

Definition at line 844 of file crazyflie_server.cpp.

Definition at line 845 of file crazyflie_server.cpp.

Definition at line 847 of file crazyflie_server.cpp.

Definition at line 846 of file crazyflie_server.cpp.

Definition at line 843 of file crazyflie_server.cpp.

Definition at line 849 of file crazyflie_server.cpp.

Definition at line 848 of file crazyflie_server.cpp.

std::string CrazyflieROS::m_tf_prefix [private]

Definition at line 813 of file crazyflie_server.cpp.

std::thread CrazyflieROS::m_thread [private]

Definition at line 862 of file crazyflie_server.cpp.

Definition at line 821 of file crazyflie_server.cpp.


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


crazyflie_driver
Author(s): Wolfgang Hoenig
autogenerated on Wed Jun 12 2019 19:20:47