gyroscope_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_GYROSCOPE_GYROSCOPE_ROS_I_H
31 #define PHIDGETS_GYROSCOPE_GYROSCOPE_ROS_I_H
32 
33 #include <memory>
34 #include <mutex>
35 #include <string>
36 
37 #include <ros/ros.h>
38 #include <std_srvs/Empty.h>
39 
40 #include "phidgets_api/gyroscope.h"
41 
42 namespace phidgets {
43 
44 class GyroscopeRosI final
45 {
46  public:
47  explicit GyroscopeRosI(ros::NodeHandle nh, ros::NodeHandle nh_private);
48 
49  private:
50  std::unique_ptr<Gyroscope> gyroscope_;
51  std::string frame_id_;
53  std::mutex gyro_mutex_;
54  double last_gyro_x_;
55  double last_gyro_y_;
56  double last_gyro_z_;
57 
63  void timerCallback(const ros::TimerEvent &event);
66  std::string server_name_;
67  std::string server_ip_;
68 
71  uint64_t data_time_zero_ns_{0};
73  uint64_t last_ros_stamp_ns_{0};
75  int64_t data_interval_ns_{0};
76  bool can_publish_{false};
79 
80  void publishLatest();
81 
82  void calibrate();
83 
84  bool calibrateService(std_srvs::Empty::Request &req,
85  std_srvs::Empty::Response &res);
86 
87  void gyroscopeChangeCallback(const double angular_rate[3],
88  const double timestamp);
89 };
90 
91 } // namespace phidgets
92 
93 #endif // PHIDGETS_GYROSCOPE_GYROSCOPE_ROS_I_H
phidgets
phidgets::GyroscopeRosI::cb_delta_epsilon_ns_
int64_t cb_delta_epsilon_ns_
Definition: gyroscope_ros_i.h:78
phidgets::GyroscopeRosI::calibrate
void calibrate()
Definition: gyroscope_ros_i.cpp:160
phidgets::GyroscopeRosI::calibrateService
bool calibrateService(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
Definition: gyroscope_ros_i.cpp:177
phidgets::GyroscopeRosI::last_data_timestamp_ns_
uint64_t last_data_timestamp_ns_
Definition: gyroscope_ros_i.h:72
phidgets::GyroscopeRosI::publishLatest
void publishLatest()
Definition: gyroscope_ros_i.cpp:186
ros::Publisher
phidgets::GyroscopeRosI::last_gyro_x_
double last_gyro_x_
Definition: gyroscope_ros_i.h:54
ros.h
phidgets::GyroscopeRosI::gyroscope_
std::unique_ptr< Gyroscope > gyroscope_
Definition: gyroscope_ros_i.h:50
phidgets::GyroscopeRosI::GyroscopeRosI
GyroscopeRosI(ros::NodeHandle nh, ros::NodeHandle nh_private)
Definition: gyroscope_ros_i.cpp:43
phidgets::GyroscopeRosI::time_resync_interval_ns_
int64_t time_resync_interval_ns_
Definition: gyroscope_ros_i.h:74
phidgets::GyroscopeRosI::data_time_zero_ns_
uint64_t data_time_zero_ns_
Definition: gyroscope_ros_i.h:71
phidgets::GyroscopeRosI::can_publish_
bool can_publish_
Definition: gyroscope_ros_i.h:76
phidgets::GyroscopeRosI::server_name_
std::string server_name_
Definition: gyroscope_ros_i.h:66
phidgets::GyroscopeRosI::last_cb_time_
ros::Time last_cb_time_
Definition: gyroscope_ros_i.h:77
phidgets::GyroscopeRosI::gyro_mutex_
std::mutex gyro_mutex_
Definition: gyroscope_ros_i.h:53
phidgets::GyroscopeRosI::cal_srv_
ros::ServiceServer cal_srv_
Definition: gyroscope_ros_i.h:61
ros::ServiceServer
phidgets::GyroscopeRosI::last_gyro_z_
double last_gyro_z_
Definition: gyroscope_ros_i.h:56
phidgets::GyroscopeRosI::last_ros_stamp_ns_
uint64_t last_ros_stamp_ns_
Definition: gyroscope_ros_i.h:73
phidgets::GyroscopeRosI::synchronize_timestamps_
bool synchronize_timestamps_
Definition: gyroscope_ros_i.h:70
phidgets::GyroscopeRosI::data_interval_ns_
int64_t data_interval_ns_
Definition: gyroscope_ros_i.h:75
phidgets::GyroscopeRosI::ros_time_zero_
ros::Time ros_time_zero_
Definition: gyroscope_ros_i.h:69
phidgets::GyroscopeRosI::angular_velocity_variance_
double angular_velocity_variance_
Definition: gyroscope_ros_i.h:52
phidgets::GyroscopeRosI::nh_private_
ros::NodeHandle nh_private_
Definition: gyroscope_ros_i.h:59
phidgets::GyroscopeRosI::gyroscopeChangeCallback
void gyroscopeChangeCallback(const double angular_rate[3], const double timestamp)
Definition: gyroscope_ros_i.cpp:237
ros::TimerEvent
phidgets::GyroscopeRosI::cal_publisher_
ros::Publisher cal_publisher_
Definition: gyroscope_ros_i.h:60
phidgets::GyroscopeRosI::timerCallback
void timerCallback(const ros::TimerEvent &event)
Definition: gyroscope_ros_i.cpp:228
phidgets::GyroscopeRosI
Definition: gyroscope_ros_i.h:44
phidgets::GyroscopeRosI::publish_rate_
int publish_rate_
Definition: gyroscope_ros_i.h:65
phidgets::GyroscopeRosI::nh_
ros::NodeHandle nh_
Definition: gyroscope_ros_i.h:58
phidgets::GyroscopeRosI::timer_
ros::Timer timer_
Definition: gyroscope_ros_i.h:64
phidgets::GyroscopeRosI::server_ip_
std::string server_ip_
Definition: gyroscope_ros_i.h:67
ros::Time
gyroscope.h
phidgets::GyroscopeRosI::frame_id_
std::string frame_id_
Definition: gyroscope_ros_i.h:51
ros::Timer
ros::NodeHandle
phidgets::GyroscopeRosI::last_gyro_y_
double last_gyro_y_
Definition: gyroscope_ros_i.h:55
phidgets::GyroscopeRosI::gyroscope_pub_
ros::Publisher gyroscope_pub_
Definition: gyroscope_ros_i.h:62


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