Public Member Functions | |
void | startGrabbing () |
void | stopGrabbing () |
ViconReceiver () | |
~ViconReceiver () | |
Private Member Functions | |
bool | calibrateSegmentCallback (vicon_bridge::viconCalibrateSegment::Request &req, vicon_bridge::viconCalibrateSegment::Response &resp) |
void | createSegment (const string subject_name, const string segment_name) |
void | createSegmentThread (const string subject_name, const string segment_name) |
void | diagnostics (diagnostic_updater::DiagnosticStatusWrapper &stat) |
bool | grabPoseCallback (vicon_bridge::viconGrabPose::Request &req, vicon_bridge::viconGrabPose::Response &resp) |
void | grabThread () |
bool | init_vicon () |
bool | process_frame () |
void | process_markers (const ros::Time &frame_time, unsigned int vicon_frame_num) |
void | process_subjects (const ros::Time &frame_time) |
bool | shutdown_vicon () |
Private Attributes | |
ros::ServiceServer | calibrate_segment_server_ |
diagnostic_updater::Updater | diag_updater |
unsigned int | droppedFrameCount |
tf::Transform | flyer_transform |
unsigned int | frame_datum |
unsigned int | frameCount |
diagnostic_updater::FrequencyStatus | freq_status_ |
bool | grab_frames_ |
boost::thread | grab_frames_thread_ |
string | host_name_ |
unsigned int | lastFrameNumber |
ros::ServiceServer | m_grab_vicon_pose_service_server |
bool | marker_data_enabled |
ros::Publisher | marker_pub_ |
double | max_freq_ |
double | min_freq_ |
unsigned int | n_markers |
unsigned int | n_unlabeled_markers |
ros::NodeHandle | nh |
ros::NodeHandle | nh_priv |
ros::Time | now_time |
bool | segment_data_enabled |
SegmentMap | segment_publishers_ |
boost::mutex | segments_mutex_ |
string | stream_mode_ |
tf::TransformBroadcaster | tf_broadcaster_ |
string | tf_ref_frame_id_ |
ros::Time | time_datum |
std::vector< std::string > | time_log_ |
string | tracked_frame_suffix_ |
bool | unlabeled_marker_data_enabled |
Definition at line 149 of file vicon_bridge.cpp.
ViconReceiver::ViconReceiver | ( | ) | [inline] |
Definition at line 207 of file vicon_bridge.cpp.
ViconReceiver::~ViconReceiver | ( | ) | [inline] |
Definition at line 239 of file vicon_bridge.cpp.
bool ViconReceiver::calibrateSegmentCallback | ( | vicon_bridge::viconCalibrateSegment::Request & | req, |
vicon_bridge::viconCalibrateSegment::Response & | resp | ||
) | [inline, private] |
Definition at line 654 of file vicon_bridge.cpp.
void ViconReceiver::createSegment | ( | const string | subject_name, |
const string | segment_name | ||
) | [inline, private] |
Definition at line 352 of file vicon_bridge.cpp.
void ViconReceiver::createSegmentThread | ( | const string | subject_name, |
const string | segment_name | ||
) | [inline, private] |
Definition at line 310 of file vicon_bridge.cpp.
void ViconReceiver::diagnostics | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [inline, private] |
Definition at line 249 of file vicon_bridge.cpp.
bool ViconReceiver::grabPoseCallback | ( | vicon_bridge::viconGrabPose::Request & | req, |
vicon_bridge::viconGrabPose::Response & | resp | ||
) | [inline, private] |
Definition at line 598 of file vicon_bridge.cpp.
void ViconReceiver::grabThread | ( | ) | [inline, private] |
Definition at line 357 of file vicon_bridge.cpp.
bool ViconReceiver::init_vicon | ( | ) | [inline, private] |
Definition at line 259 of file vicon_bridge.cpp.
bool ViconReceiver::process_frame | ( | ) | [inline, private] |
Definition at line 398 of file vicon_bridge.cpp.
void ViconReceiver::process_markers | ( | const ros::Time & | frame_time, |
unsigned int | vicon_frame_num | ||
) | [inline, private] |
Definition at line 517 of file vicon_bridge.cpp.
void ViconReceiver::process_subjects | ( | const ros::Time & | frame_time | ) | [inline, private] |
Definition at line 437 of file vicon_bridge.cpp.
bool ViconReceiver::shutdown_vicon | ( | ) | [inline, private] |
Definition at line 387 of file vicon_bridge.cpp.
void ViconReceiver::startGrabbing | ( | ) | [inline] |
Definition at line 193 of file vicon_bridge.cpp.
void ViconReceiver::stopGrabbing | ( | ) | [inline] |
Definition at line 201 of file vicon_bridge.cpp.
Definition at line 173 of file vicon_bridge.cpp.
diagnostic_updater::Updater ViconReceiver::diag_updater [private] |
Definition at line 155 of file vicon_bridge.cpp.
unsigned int ViconReceiver::droppedFrameCount [private] |
Definition at line 177 of file vicon_bridge.cpp.
tf::Transform ViconReceiver::flyer_transform [private] |
Definition at line 169 of file vicon_bridge.cpp.
unsigned int ViconReceiver::frame_datum [private] |
Definition at line 179 of file vicon_bridge.cpp.
unsigned int ViconReceiver::frameCount [private] |
Definition at line 176 of file vicon_bridge.cpp.
diagnostic_updater::FrequencyStatus ViconReceiver::freq_status_ [private] |
Definition at line 158 of file vicon_bridge.cpp.
bool ViconReceiver::grab_frames_ [private] |
Definition at line 186 of file vicon_bridge.cpp.
boost::thread ViconReceiver::grab_frames_thread_ [private] |
Definition at line 187 of file vicon_bridge.cpp.
string ViconReceiver::host_name_ [private] |
Definition at line 161 of file vicon_bridge.cpp.
unsigned int ViconReceiver::lastFrameNumber [private] |
Definition at line 175 of file vicon_bridge.cpp.
Definition at line 172 of file vicon_bridge.cpp.
bool ViconReceiver::marker_data_enabled [private] |
Definition at line 183 of file vicon_bridge.cpp.
ros::Publisher ViconReceiver::marker_pub_ [private] |
Definition at line 165 of file vicon_bridge.cpp.
double ViconReceiver::max_freq_ [private] |
Definition at line 157 of file vicon_bridge.cpp.
double ViconReceiver::min_freq_ [private] |
Definition at line 156 of file vicon_bridge.cpp.
unsigned int ViconReceiver::n_markers [private] |
Definition at line 180 of file vicon_bridge.cpp.
unsigned int ViconReceiver::n_unlabeled_markers [private] |
Definition at line 181 of file vicon_bridge.cpp.
ros::NodeHandle ViconReceiver::nh [private] |
Definition at line 152 of file vicon_bridge.cpp.
ros::NodeHandle ViconReceiver::nh_priv [private] |
Definition at line 153 of file vicon_bridge.cpp.
ros::Time ViconReceiver::now_time [private] |
Definition at line 170 of file vicon_bridge.cpp.
bool ViconReceiver::segment_data_enabled [private] |
Definition at line 182 of file vicon_bridge.cpp.
SegmentMap ViconReceiver::segment_publishers_ [private] |
Definition at line 188 of file vicon_bridge.cpp.
boost::mutex ViconReceiver::segments_mutex_ [private] |
Definition at line 189 of file vicon_bridge.cpp.
string ViconReceiver::stream_mode_ [private] |
Definition at line 160 of file vicon_bridge.cpp.
tf::TransformBroadcaster ViconReceiver::tf_broadcaster_ [private] |
Definition at line 167 of file vicon_bridge.cpp.
string ViconReceiver::tf_ref_frame_id_ [private] |
Definition at line 162 of file vicon_bridge.cpp.
ros::Time ViconReceiver::time_datum [private] |
Definition at line 178 of file vicon_bridge.cpp.
std::vector<std::string> ViconReceiver::time_log_ [private] |
Definition at line 190 of file vicon_bridge.cpp.
string ViconReceiver::tracked_frame_suffix_ [private] |
Definition at line 163 of file vicon_bridge.cpp.
bool ViconReceiver::unlabeled_marker_data_enabled [private] |
Definition at line 184 of file vicon_bridge.cpp.