Public Member Functions | Private Member Functions | Private Attributes | List of all members
phidgets::GyroscopeRosI Class Referencefinal

#include <gyroscope_ros_i.h>

Public Member Functions

 GyroscopeRosI (ros::NodeHandle nh, ros::NodeHandle nh_private)
 

Private Member Functions

void calibrate ()
 
bool calibrateService (std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
 
void gyroscopeChangeCallback (const double angular_rate[3], const double timestamp)
 
void publishLatest ()
 
void timerCallback (const ros::TimerEvent &event)
 

Private Attributes

double angular_velocity_variance_
 
ros::Publisher cal_publisher_
 
ros::ServiceServer cal_srv_
 
bool can_publish_ {false}
 
int64_t cb_delta_epsilon_ns_ {0}
 
int64_t data_interval_ns_ {0}
 
uint64_t data_time_zero_ns_ {0}
 
std::string frame_id_
 
std::mutex gyro_mutex_
 
std::unique_ptr< Gyroscopegyroscope_
 
ros::Publisher gyroscope_pub_
 
ros::Time last_cb_time_
 
uint64_t last_data_timestamp_ns_ {0}
 
double last_gyro_x_
 
double last_gyro_y_
 
double last_gyro_z_
 
uint64_t last_ros_stamp_ns_ {0}
 
ros::NodeHandle nh_
 
ros::NodeHandle nh_private_
 
int publish_rate_
 
ros::Time ros_time_zero_
 
std::string server_ip_
 
std::string server_name_
 
bool synchronize_timestamps_ {true}
 
int64_t time_resync_interval_ns_ {0}
 
ros::Timer timer_
 

Detailed Description

Definition at line 44 of file gyroscope_ros_i.h.

Constructor & Destructor Documentation

◆ GyroscopeRosI()

phidgets::GyroscopeRosI::GyroscopeRosI ( ros::NodeHandle  nh,
ros::NodeHandle  nh_private 
)
explicit

Definition at line 43 of file gyroscope_ros_i.cpp.

Member Function Documentation

◆ calibrate()

void phidgets::GyroscopeRosI::calibrate ( )
private

Definition at line 160 of file gyroscope_ros_i.cpp.

◆ calibrateService()

bool phidgets::GyroscopeRosI::calibrateService ( std_srvs::Empty::Request &  req,
std_srvs::Empty::Response &  res 
)
private

Definition at line 177 of file gyroscope_ros_i.cpp.

◆ gyroscopeChangeCallback()

void phidgets::GyroscopeRosI::gyroscopeChangeCallback ( const double  angular_rate[3],
const double  timestamp 
)
private

Definition at line 237 of file gyroscope_ros_i.cpp.

◆ publishLatest()

void phidgets::GyroscopeRosI::publishLatest ( )
private

Definition at line 186 of file gyroscope_ros_i.cpp.

◆ timerCallback()

void phidgets::GyroscopeRosI::timerCallback ( const ros::TimerEvent event)
private

Definition at line 228 of file gyroscope_ros_i.cpp.

Member Data Documentation

◆ angular_velocity_variance_

double phidgets::GyroscopeRosI::angular_velocity_variance_
private

Definition at line 52 of file gyroscope_ros_i.h.

◆ cal_publisher_

ros::Publisher phidgets::GyroscopeRosI::cal_publisher_
private

Definition at line 60 of file gyroscope_ros_i.h.

◆ cal_srv_

ros::ServiceServer phidgets::GyroscopeRosI::cal_srv_
private

Definition at line 61 of file gyroscope_ros_i.h.

◆ can_publish_

bool phidgets::GyroscopeRosI::can_publish_ {false}
private

Definition at line 76 of file gyroscope_ros_i.h.

◆ cb_delta_epsilon_ns_

int64_t phidgets::GyroscopeRosI::cb_delta_epsilon_ns_ {0}
private

Definition at line 78 of file gyroscope_ros_i.h.

◆ data_interval_ns_

int64_t phidgets::GyroscopeRosI::data_interval_ns_ {0}
private

Definition at line 75 of file gyroscope_ros_i.h.

◆ data_time_zero_ns_

uint64_t phidgets::GyroscopeRosI::data_time_zero_ns_ {0}
private

Definition at line 71 of file gyroscope_ros_i.h.

◆ frame_id_

std::string phidgets::GyroscopeRosI::frame_id_
private

Definition at line 51 of file gyroscope_ros_i.h.

◆ gyro_mutex_

std::mutex phidgets::GyroscopeRosI::gyro_mutex_
private

Definition at line 53 of file gyroscope_ros_i.h.

◆ gyroscope_

std::unique_ptr<Gyroscope> phidgets::GyroscopeRosI::gyroscope_
private

Definition at line 50 of file gyroscope_ros_i.h.

◆ gyroscope_pub_

ros::Publisher phidgets::GyroscopeRosI::gyroscope_pub_
private

Definition at line 62 of file gyroscope_ros_i.h.

◆ last_cb_time_

ros::Time phidgets::GyroscopeRosI::last_cb_time_
private

Definition at line 77 of file gyroscope_ros_i.h.

◆ last_data_timestamp_ns_

uint64_t phidgets::GyroscopeRosI::last_data_timestamp_ns_ {0}
private

Definition at line 72 of file gyroscope_ros_i.h.

◆ last_gyro_x_

double phidgets::GyroscopeRosI::last_gyro_x_
private

Definition at line 54 of file gyroscope_ros_i.h.

◆ last_gyro_y_

double phidgets::GyroscopeRosI::last_gyro_y_
private

Definition at line 55 of file gyroscope_ros_i.h.

◆ last_gyro_z_

double phidgets::GyroscopeRosI::last_gyro_z_
private

Definition at line 56 of file gyroscope_ros_i.h.

◆ last_ros_stamp_ns_

uint64_t phidgets::GyroscopeRosI::last_ros_stamp_ns_ {0}
private

Definition at line 73 of file gyroscope_ros_i.h.

◆ nh_

ros::NodeHandle phidgets::GyroscopeRosI::nh_
private

Definition at line 58 of file gyroscope_ros_i.h.

◆ nh_private_

ros::NodeHandle phidgets::GyroscopeRosI::nh_private_
private

Definition at line 59 of file gyroscope_ros_i.h.

◆ publish_rate_

int phidgets::GyroscopeRosI::publish_rate_
private

Definition at line 65 of file gyroscope_ros_i.h.

◆ ros_time_zero_

ros::Time phidgets::GyroscopeRosI::ros_time_zero_
private

Definition at line 69 of file gyroscope_ros_i.h.

◆ server_ip_

std::string phidgets::GyroscopeRosI::server_ip_
private

Definition at line 67 of file gyroscope_ros_i.h.

◆ server_name_

std::string phidgets::GyroscopeRosI::server_name_
private

Definition at line 66 of file gyroscope_ros_i.h.

◆ synchronize_timestamps_

bool phidgets::GyroscopeRosI::synchronize_timestamps_ {true}
private

Definition at line 70 of file gyroscope_ros_i.h.

◆ time_resync_interval_ns_

int64_t phidgets::GyroscopeRosI::time_resync_interval_ns_ {0}
private

Definition at line 74 of file gyroscope_ros_i.h.

◆ timer_

ros::Timer phidgets::GyroscopeRosI::timer_
private

Definition at line 64 of file gyroscope_ros_i.h.


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


phidgets_gyroscope
Author(s): Chris Lalancette
autogenerated on Sun May 11 2025 02:20:32