spatial_ros_i.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2019, Open Source Robotics Foundation
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef PHIDGETS_SPATIAL_SPATIAL_ROS_I_H
31 #define PHIDGETS_SPATIAL_SPATIAL_ROS_I_H
32 
33 #include <memory>
34 #include <mutex>
35 #include <string>
36 
37 #include <ros/ros.h>
38 #include <ros/service_server.h>
39 #include <std_srvs/Empty.h>
40 
41 #include "phidgets_api/spatial.h"
42 
43 namespace phidgets {
44 
45 const float G = 9.80665;
46 
47 class SpatialRosI final
48 {
49  public:
50  explicit SpatialRosI(ros::NodeHandle nh, ros::NodeHandle nh_private);
51 
52  private:
55  std::string frame_id_;
56  std::mutex spatial_mutex_;
57  void timerCallback(const ros::TimerEvent &event);
60  std::string server_name_;
61  std::string server_ip_;
66 
69  uint64_t data_time_zero_ns_{0};
71  uint64_t last_ros_stamp_ns_{0};
73  int64_t data_interval_ns_{0};
74  bool can_publish_{false};
77 
78  void calibrate();
79 
80  bool calibrateService(std_srvs::Empty::Request &req,
81  std_srvs::Empty::Response &res);
82 
83  std::unique_ptr<Spatial> spatial_;
84 
85  // Accelerometer
87  double last_accel_x_;
88  double last_accel_y_;
89  double last_accel_z_;
90 
91  // Gyroscope
93  double last_gyro_x_;
94  double last_gyro_y_;
95  double last_gyro_z_;
96 
97  // Magnetometer
99  double last_mag_x_;
100  double last_mag_y_;
101  double last_mag_z_;
102 
103  // Onboard orientation estimation results
104  double last_quat_w_;
105  double last_quat_x_;
106  double last_quat_y_;
107  double last_quat_z_;
108 
109  void publishLatest();
110 
111  void spatialDataCallback(const double acceleration[3],
112  const double angular_rate[3],
113  const double magnetic_field[3], double timestamp);
114  void spatialAlgorithmDataCallback(const double quaternion[4],
115  double timestamp);
116  void attachCallback();
117  void detachCallback();
118 };
119 
120 } // namespace phidgets
121 
122 #endif // PHIDGETS_SPATIAL_SPATIAL_ROS_I_H
phidgets
phidgets::SpatialRosI::last_accel_x_
double last_accel_x_
Definition: spatial_ros_i.h:87
phidgets::SpatialRosI::spatial_mutex_
std::mutex spatial_mutex_
Definition: spatial_ros_i.h:56
phidgets::SpatialRosI::last_ros_stamp_ns_
uint64_t last_ros_stamp_ns_
Definition: spatial_ros_i.h:71
phidgets::SpatialRosI::cal_srv_
ros::ServiceServer cal_srv_
Definition: spatial_ros_i.h:63
phidgets::SpatialRosI::frame_id_
std::string frame_id_
Definition: spatial_ros_i.h:55
ros::Publisher
phidgets::SpatialRosI::last_quat_y_
double last_quat_y_
Definition: spatial_ros_i.h:106
ros.h
phidgets::SpatialRosI::nh_private_
ros::NodeHandle nh_private_
Definition: spatial_ros_i.h:54
phidgets::SpatialRosI::calibrateService
bool calibrateService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: spatial_ros_i.cpp:316
phidgets::SpatialRosI::spatialAlgorithmDataCallback
void spatialAlgorithmDataCallback(const double quaternion[4], double timestamp)
Definition: spatial_ros_i.cpp:551
phidgets::SpatialRosI::spatialDataCallback
void spatialDataCallback(const double acceleration[3], const double angular_rate[3], const double magnetic_field[3], double timestamp)
Definition: spatial_ros_i.cpp:417
phidgets::SpatialRosI::timer_
ros::Timer timer_
Definition: spatial_ros_i.h:58
phidgets::SpatialRosI::angular_velocity_variance_
double angular_velocity_variance_
Definition: spatial_ros_i.h:92
phidgets::SpatialRosI::ros_time_zero_
ros::Time ros_time_zero_
Definition: spatial_ros_i.h:67
phidgets::SpatialRosI
Definition: spatial_ros_i.h:47
phidgets::SpatialRosI::synchronize_timestamps_
bool synchronize_timestamps_
Definition: spatial_ros_i.h:68
phidgets::SpatialRosI::publish_rate_
int publish_rate_
Definition: spatial_ros_i.h:59
ros::ServiceServer
phidgets::SpatialRosI::last_gyro_z_
double last_gyro_z_
Definition: spatial_ros_i.h:95
phidgets::SpatialRosI::calibrate
void calibrate()
Definition: spatial_ros_i.cpp:325
phidgets::SpatialRosI::can_publish_
bool can_publish_
Definition: spatial_ros_i.h:74
spatial.h
phidgets::SpatialRosI::last_quat_w_
double last_quat_w_
Definition: spatial_ros_i.h:104
phidgets::SpatialRosI::last_quat_x_
double last_quat_x_
Definition: spatial_ros_i.h:105
phidgets::SpatialRosI::data_time_zero_ns_
uint64_t data_time_zero_ns_
Definition: spatial_ros_i.h:69
phidgets::SpatialRosI::cb_delta_epsilon_ns_
int64_t cb_delta_epsilon_ns_
Definition: spatial_ros_i.h:76
phidgets::SpatialRosI::magnetic_field_pub_
ros::Publisher magnetic_field_pub_
Definition: spatial_ros_i.h:65
phidgets::SpatialRosI::SpatialRosI
SpatialRosI(ros::NodeHandle nh, ros::NodeHandle nh_private)
Definition: spatial_ros_i.cpp:46
phidgets::SpatialRosI::magnetic_field_variance_
double magnetic_field_variance_
Definition: spatial_ros_i.h:98
phidgets::SpatialRosI::timerCallback
void timerCallback(const ros::TimerEvent &event)
Definition: spatial_ros_i.cpp:581
phidgets::SpatialRosI::last_mag_z_
double last_mag_z_
Definition: spatial_ros_i.h:101
ros::TimerEvent
phidgets::SpatialRosI::publishLatest
void publishLatest()
Definition: spatial_ros_i.cpp:342
phidgets::SpatialRosI::last_accel_y_
double last_accel_y_
Definition: spatial_ros_i.h:88
phidgets::SpatialRosI::imu_pub_
ros::Publisher imu_pub_
Definition: spatial_ros_i.h:64
phidgets::SpatialRosI::last_mag_y_
double last_mag_y_
Definition: spatial_ros_i.h:100
phidgets::SpatialRosI::last_gyro_x_
double last_gyro_x_
Definition: spatial_ros_i.h:93
phidgets::SpatialRosI::last_quat_z_
double last_quat_z_
Definition: spatial_ros_i.h:107
phidgets::SpatialRosI::last_accel_z_
double last_accel_z_
Definition: spatial_ros_i.h:89
ros::Time
phidgets::SpatialRosI::time_resync_interval_ns_
int64_t time_resync_interval_ns_
Definition: spatial_ros_i.h:72
phidgets::SpatialRosI::server_name_
std::string server_name_
Definition: spatial_ros_i.h:60
phidgets::SpatialRosI::last_gyro_y_
double last_gyro_y_
Definition: spatial_ros_i.h:94
phidgets::SpatialRosI::nh_
ros::NodeHandle nh_
Definition: spatial_ros_i.h:53
phidgets::SpatialRosI::linear_acceleration_variance_
double linear_acceleration_variance_
Definition: spatial_ros_i.h:86
phidgets::SpatialRosI::cal_publisher_
ros::Publisher cal_publisher_
Definition: spatial_ros_i.h:62
phidgets::SpatialRosI::spatial_
std::unique_ptr< Spatial > spatial_
Definition: spatial_ros_i.h:83
phidgets::SpatialRosI::detachCallback
void detachCallback()
Definition: spatial_ros_i.cpp:576
phidgets::G
const float G
Definition: spatial_ros_i.h:45
phidgets::SpatialRosI::server_ip_
std::string server_ip_
Definition: spatial_ros_i.h:61
phidgets::SpatialRosI::data_interval_ns_
int64_t data_interval_ns_
Definition: spatial_ros_i.h:73
phidgets::SpatialRosI::attachCallback
void attachCallback()
Definition: spatial_ros_i.cpp:561
service_server.h
ros::Timer
phidgets::SpatialRosI::last_cb_time_
ros::Time last_cb_time_
Definition: spatial_ros_i.h:75
phidgets::SpatialRosI::last_mag_x_
double last_mag_x_
Definition: spatial_ros_i.h:99
ros::NodeHandle
phidgets::SpatialRosI::last_data_timestamp_ns_
uint64_t last_data_timestamp_ns_
Definition: spatial_ros_i.h:70


phidgets_spatial
Author(s): Ivan Dryanovski
autogenerated on Sat Dec 2 2023 03:18:58