#include <attitude_indicator_plugin.h>
Public Member Functions | |
AttitudeIndicatorPlugin () | |
void | Draw (double x, double y, double scale) |
QWidget * | GetConfigWidget (QWidget *parent) |
bool | Initialize (QGLWidget *canvas) |
void | LoadConfig (const YAML::Node &node, const std::string &path) |
void | SaveConfig (YAML::Emitter &emitter, const std::string &path) |
void | Shutdown () |
void | Transform () |
virtual | ~AttitudeIndicatorPlugin () |
Protected Slots | |
void | SelectTopic () |
void | TopicEdited () |
Protected Member Functions | |
void | drawBackground () |
void | drawBall () |
void | drawPanel () |
void | PrintError (const std::string &message) |
void | PrintInfo (const std::string &message) |
void | PrintWarning (const std::string &message) |
void | timerEvent (QTimerEvent *) |
Private Member Functions | |
void | AttitudeCallbackImu (const sensor_msgs::ImuConstPtr &imu) |
void | AttitudeCallbackOdom (const nav_msgs::OdometryConstPtr &odometry) |
void | AttitudeCallbackPose (const geometry_msgs::PoseConstPtr &pose) |
void | handleMessage (const topic_tools::ShapeShifter::ConstPtr &msg) |
Private Attributes | |
tf::Quaternion | attitude_orientation_ |
QWidget * | config_widget_ |
ros::Subscriber | odometry_sub_ |
double | pitch_ |
PlaceableWindowProxy | placer_ |
double | roll_ |
std::string | topic_ |
std::vector< std::string > | topics_ |
Ui::attitude_indicator_config | ui_ |
double | yaw_ |
Definition at line 63 of file attitude_indicator_plugin.h.
Definition at line 59 of file attitude_indicator_plugin.cpp.
Definition at line 85 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::AttitudeCallbackImu | ( | const sensor_msgs::ImuConstPtr & | imu | ) | [private] |
Definition at line 160 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::AttitudeCallbackOdom | ( | const nav_msgs::OdometryConstPtr & | odometry | ) | [private] |
Definition at line 142 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::AttitudeCallbackPose | ( | const geometry_msgs::PoseConstPtr & | pose | ) | [private] |
Definition at line 178 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::Draw | ( | double | x, |
double | y, | ||
double | scale | ||
) | [virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 288 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::drawBackground | ( | ) | [protected] |
Definition at line 329 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::drawBall | ( | ) | [protected] |
Definition at line 236 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::drawPanel | ( | ) | [protected] |
Definition at line 345 of file attitude_indicator_plugin.cpp.
QWidget * mapviz_plugins::AttitudeIndicatorPlugin::GetConfigWidget | ( | QWidget * | parent | ) | [virtual] |
Reimplemented from mapviz::MapvizPlugin.
Definition at line 211 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::handleMessage | ( | const topic_tools::ShapeShifter::ConstPtr & | msg | ) | [private] |
Definition at line 122 of file attitude_indicator_plugin.cpp.
bool mapviz_plugins::AttitudeIndicatorPlugin::Initialize | ( | QGLWidget * | canvas | ) | [virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 217 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::LoadConfig | ( | const YAML::Node & | node, |
const std::string & | path | ||
) | [virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 372 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::PrintError | ( | const std::string & | message | ) | [protected, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 196 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::PrintInfo | ( | const std::string & | message | ) | [protected, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 201 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::PrintWarning | ( | const std::string & | message | ) | [protected, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 206 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::SaveConfig | ( | YAML::Emitter & | emitter, |
const std::string & | path | ||
) | [virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 413 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::SelectTopic | ( | ) | [protected, slot] |
Definition at line 89 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::Shutdown | ( | ) | [virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 226 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::timerEvent | ( | QTimerEvent * | ) | [protected] |
Definition at line 231 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::TopicEdited | ( | ) | [protected, slot] |
Definition at line 102 of file attitude_indicator_plugin.cpp.
void mapviz_plugins::AttitudeIndicatorPlugin::Transform | ( | ) | [inline, virtual] |
Implements mapviz::MapvizPlugin.
Definition at line 76 of file attitude_indicator_plugin.h.
Definition at line 104 of file attitude_indicator_plugin.h.
QWidget* mapviz_plugins::AttitudeIndicatorPlugin::config_widget_ [private] |
Definition at line 109 of file attitude_indicator_plugin.h.
Definition at line 110 of file attitude_indicator_plugin.h.
double mapviz_plugins::AttitudeIndicatorPlugin::pitch_ [private] |
Definition at line 105 of file attitude_indicator_plugin.h.
Definition at line 108 of file attitude_indicator_plugin.h.
double mapviz_plugins::AttitudeIndicatorPlugin::roll_ [private] |
Definition at line 106 of file attitude_indicator_plugin.h.
std::string mapviz_plugins::AttitudeIndicatorPlugin::topic_ [private] |
Definition at line 111 of file attitude_indicator_plugin.h.
std::vector<std::string> mapviz_plugins::AttitudeIndicatorPlugin::topics_ [private] |
Definition at line 112 of file attitude_indicator_plugin.h.
Ui::attitude_indicator_config mapviz_plugins::AttitudeIndicatorPlugin::ui_ [private] |
Definition at line 113 of file attitude_indicator_plugin.h.
double mapviz_plugins::AttitudeIndicatorPlugin::yaw_ [private] |
Definition at line 107 of file attitude_indicator_plugin.h.