asctec::AsctecProc Class Reference

#include <asctec_proc.h>

List of all members.

Public Member Functions

 AsctecProc (ros::NodeHandle nh, ros::NodeHandle nh_private)
virtual ~AsctecProc ()

Private Member Functions

void assembleCtrlCommands ()
void cmdPitchCallback (const std_msgs::Float64ConstPtr &cmd_pitch_msg)
void cmdRollCallback (const std_msgs::Float64ConstPtr &cmd_roll_msg)
void cmdThrustCallback (const std_msgs::Float64ConstPtr &cmd_thrust_msg)
void cmdYawCallback (const std_msgs::Float64ConstPtr &cmd_yaw_rate_msg)
void createHeightFilteredMsg (const asctec_msgs::IMUCalcDataConstPtr &imu_calcdata_msg, mav_msgs::HeightPtr &height_filtered_msg)
void createHeightMsg (const asctec_msgs::IMUCalcDataConstPtr &imu_calcdata_msg, mav_msgs::HeightPtr &height_msg)
void createImuMsg (const asctec_msgs::IMUCalcDataConstPtr &imu_calcdata_msg, sensor_msgs::ImuPtr &imu_msg)
bool getMotorsOnOff (mav_msgs::GetMotorsOnOff::Request &req, mav_msgs::GetMotorsOnOff::Response &res)
void imuCalcDataCallback (const asctec_msgs::IMUCalcDataConstPtr &imu_calcdata_msg)
void initializeParams ()
void llStatusCallback (const asctec_msgs::LLStatusPtr &ll_status_msg)
void publishCtrlInputMsg ()
bool setMotorsOnOff (mav_msgs::SetMotorsOnOff::Request &req, mav_msgs::SetMotorsOnOff::Response &res)
void startMotors ()
void stopMotors ()

Private Attributes

ros::Subscriber cmd_pitch_subscriber_
ros::Subscriber cmd_roll_subscriber_
ros::Subscriber cmd_thrust_subscriber_
ros::Subscriber cmd_yaw_subscriber_
ros::Publisher ctrl_input_publisher_
asctec_msgs::CtrlInputPtr ctrl_input_toggle_msg_
asctec_msgs::CtrlInputPtr ctrl_input_zero_msg_
int ctrl_pitch_
int ctrl_roll_
int ctrl_thrust_
int ctrl_yaw_
bool enable_ctrl_pitch_
bool enable_ctrl_roll_
bool enable_ctrl_thrust_
bool enable_ctrl_yaw_
bool enable_state_changes_
bool engaging_
ros::Subscriber estop_subscriber_
ros::ServiceServer get_motors_on_off_srv_
ros::Publisher height_filtered_publisher_
ros::Publisher height_publisher_
ros::Subscriber imu_calcdata_subscriber_
ros::Publisher imu_publisher_
ros::Subscriber ll_status_subscriber_
int max_ctrl_pitch_
int max_ctrl_roll_
int max_ctrl_thrust_
int max_ctrl_yaw_
bool motors_on_
ros::NodeHandle nh_
ros::NodeHandle nh_private_
ros::ServiceServer set_motors_on_off_srv_
boost::mutex state_mutex_
ros::Subscriber state_subscriber_

Detailed Description

Definition at line 39 of file asctec_proc.h.


Constructor & Destructor Documentation

asctec::AsctecProc::AsctecProc ( ros::NodeHandle  nh,
ros::NodeHandle  nh_private 
)

Definition at line 27 of file asctec_proc.cpp.

asctec::AsctecProc::~AsctecProc (  )  [virtual]

Definition at line 103 of file asctec_proc.cpp.


Member Function Documentation

void asctec::AsctecProc::assembleCtrlCommands (  )  [private]

Definition at line 447 of file asctec_proc.cpp.

void asctec::AsctecProc::cmdPitchCallback ( const std_msgs::Float64ConstPtr &  cmd_pitch_msg  )  [private]

Definition at line 202 of file asctec_proc.cpp.

void asctec::AsctecProc::cmdRollCallback ( const std_msgs::Float64ConstPtr &  cmd_roll_msg  )  [private]

Definition at line 174 of file asctec_proc.cpp.

void asctec::AsctecProc::cmdThrustCallback ( const std_msgs::Float64ConstPtr &  cmd_thrust_msg  )  [private]

Definition at line 258 of file asctec_proc.cpp.

void asctec::AsctecProc::cmdYawCallback ( const std_msgs::Float64ConstPtr &  cmd_yaw_rate_msg  )  [private]

Definition at line 230 of file asctec_proc.cpp.

void asctec::AsctecProc::createHeightFilteredMsg ( const asctec_msgs::IMUCalcDataConstPtr &  imu_calcdata_msg,
mav_msgs::HeightPtr &  height_filtered_msg 
) [private]

Definition at line 338 of file asctec_proc.cpp.

void asctec::AsctecProc::createHeightMsg ( const asctec_msgs::IMUCalcDataConstPtr &  imu_calcdata_msg,
mav_msgs::HeightPtr &  height_msg 
) [private]

Definition at line 327 of file asctec_proc.cpp.

void asctec::AsctecProc::createImuMsg ( const asctec_msgs::IMUCalcDataConstPtr &  imu_calcdata_msg,
sensor_msgs::ImuPtr &  imu_msg 
) [private]

Definition at line 349 of file asctec_proc.cpp.

bool asctec::AsctecProc::getMotorsOnOff ( mav_msgs::GetMotorsOnOff::Request &  req,
mav_msgs::GetMotorsOnOff::Response &  res 
) [private]

Definition at line 158 of file asctec_proc.cpp.

void asctec::AsctecProc::imuCalcDataCallback ( const asctec_msgs::IMUCalcDataConstPtr &  imu_calcdata_msg  )  [private]

Definition at line 286 of file asctec_proc.cpp.

void asctec::AsctecProc::initializeParams (  )  [private]

Definition at line 109 of file asctec_proc.cpp.

void asctec::AsctecProc::llStatusCallback ( const asctec_msgs::LLStatusPtr &  ll_status_msg  )  [private]

Definition at line 168 of file asctec_proc.cpp.

void asctec::AsctecProc::publishCtrlInputMsg (  )  [private]

Definition at line 478 of file asctec_proc.cpp.

bool asctec::AsctecProc::setMotorsOnOff ( mav_msgs::SetMotorsOnOff::Request &  req,
mav_msgs::SetMotorsOnOff::Response &  res 
) [private]

Definition at line 133 of file asctec_proc.cpp.

void asctec::AsctecProc::startMotors (  )  [private]

Definition at line 403 of file asctec_proc.cpp.

void asctec::AsctecProc::stopMotors (  )  [private]

Definition at line 425 of file asctec_proc.cpp.


Member Data Documentation

ros::Subscriber asctec::AsctecProc::cmd_pitch_subscriber_ [private]

Definition at line 49 of file asctec_proc.h.

ros::Subscriber asctec::AsctecProc::cmd_roll_subscriber_ [private]

Definition at line 48 of file asctec_proc.h.

ros::Subscriber asctec::AsctecProc::cmd_thrust_subscriber_ [private]

Definition at line 47 of file asctec_proc.h.

ros::Subscriber asctec::AsctecProc::cmd_yaw_subscriber_ [private]

Definition at line 50 of file asctec_proc.h.

Definition at line 59 of file asctec_proc.h.

asctec_msgs::CtrlInputPtr asctec::AsctecProc::ctrl_input_toggle_msg_ [private]

Definition at line 73 of file asctec_proc.h.

asctec_msgs::CtrlInputPtr asctec::AsctecProc::ctrl_input_zero_msg_ [private]

Definition at line 74 of file asctec_proc.h.

Definition at line 69 of file asctec_proc.h.

Definition at line 68 of file asctec_proc.h.

Definition at line 71 of file asctec_proc.h.

Definition at line 70 of file asctec_proc.h.

Definition at line 83 of file asctec_proc.h.

Definition at line 82 of file asctec_proc.h.

Definition at line 81 of file asctec_proc.h.

Definition at line 84 of file asctec_proc.h.

Definition at line 86 of file asctec_proc.h.

Definition at line 77 of file asctec_proc.h.

ros::Subscriber asctec::AsctecProc::estop_subscriber_ [private]

Definition at line 54 of file asctec_proc.h.

ros::ServiceServer asctec::AsctecProc::get_motors_on_off_srv_ [private]

Definition at line 62 of file asctec_proc.h.

Definition at line 58 of file asctec_proc.h.

ros::Publisher asctec::AsctecProc::height_publisher_ [private]

Definition at line 57 of file asctec_proc.h.

Definition at line 52 of file asctec_proc.h.

ros::Publisher asctec::AsctecProc::imu_publisher_ [private]

Definition at line 56 of file asctec_proc.h.

ros::Subscriber asctec::AsctecProc::ll_status_subscriber_ [private]

Definition at line 51 of file asctec_proc.h.

Definition at line 90 of file asctec_proc.h.

Definition at line 89 of file asctec_proc.h.

Definition at line 88 of file asctec_proc.h.

Definition at line 91 of file asctec_proc.h.

Definition at line 76 of file asctec_proc.h.

ros::NodeHandle asctec::AsctecProc::nh_ [private]

Definition at line 44 of file asctec_proc.h.

ros::NodeHandle asctec::AsctecProc::nh_private_ [private]

Definition at line 45 of file asctec_proc.h.

ros::ServiceServer asctec::AsctecProc::set_motors_on_off_srv_ [private]

Definition at line 61 of file asctec_proc.h.

boost::mutex asctec::AsctecProc::state_mutex_ [private]

Definition at line 66 of file asctec_proc.h.

ros::Subscriber asctec::AsctecProc::state_subscriber_ [private]

Definition at line 53 of file asctec_proc.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs


asctec_proc
Author(s): Ivan Dryanovski
autogenerated on Fri Jan 11 09:40:06 2013