Go to the documentation of this file.
30 #ifndef PHIDGETS_SPATIAL_SPATIAL_ROS_I_H
31 #define PHIDGETS_SPATIAL_SPATIAL_ROS_I_H
39 #include <std_srvs/Empty.h>
45 const float G = 9.80665;
81 std_srvs::Empty::Response &res);
112 const double angular_rate[3],
113 const double magnetic_field[3],
double timestamp);
122 #endif // PHIDGETS_SPATIAL_SPATIAL_ROS_I_H
std::mutex spatial_mutex_
uint64_t last_ros_stamp_ns_
ros::ServiceServer cal_srv_
ros::NodeHandle nh_private_
bool calibrateService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
void spatialAlgorithmDataCallback(const double quaternion[4], double timestamp)
void spatialDataCallback(const double acceleration[3], const double angular_rate[3], const double magnetic_field[3], double timestamp)
double angular_velocity_variance_
bool synchronize_timestamps_
uint64_t data_time_zero_ns_
int64_t cb_delta_epsilon_ns_
ros::Publisher magnetic_field_pub_
SpatialRosI(ros::NodeHandle nh, ros::NodeHandle nh_private)
double magnetic_field_variance_
void timerCallback(const ros::TimerEvent &event)
int64_t time_resync_interval_ns_
double linear_acceleration_variance_
ros::Publisher cal_publisher_
std::unique_ptr< Spatial > spatial_
int64_t data_interval_ns_
uint64_t last_data_timestamp_ns_
phidgets_spatial
Author(s): Ivan Dryanovski
autogenerated on Sat Dec 2 2023 03:18:58