Skip to content

Commit 78bf6da

Browse files
committed
Major refactoring of diagnostics (CCNYRoboticsLab#20)
- Remove all diagnostics logic from phidget_api - Add diagnostics to phidgets_imu - Connect/disconnect/error states are propogated from callbacks - Periodic updates for diagnostics through processImuData() - Add Frequency and Timestamp (drift) diagnostics for imu/data_raw topic
1 parent 8c89007 commit 78bf6da

File tree

7 files changed

+109
-64
lines changed

7 files changed

+109
-64
lines changed

phidgets_api/include/phidgets_api/phidget.h

Lines changed: 0 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -33,8 +33,6 @@
3333

3434
#include <phidgets_api/phidget21.h>
3535

36-
#include <diagnostic_updater/diagnostic_updater.h>
37-
#include <diagnostic_updater/publisher.h>
3836
#include <iostream>
3937
#include <algorithm>
4038
#include <string>
@@ -50,21 +48,6 @@ class Phidget
5048
Phidget();
5149
~Phidget();
5250

53-
/**@brief updater object of class Update. Used to add diagnostic tasks, set ID etc. refer package API.
54-
* Added for diagnostics */
55-
diagnostic_updater::Updater updater;
56-
57-
/**@brief This bool is public to allow to know when 1000s condition in imu_ros_i.cpp is over and need
58-
* to report a connection error.
59-
* Added for diagnostics */
60-
bool is_connected;
61-
62-
/**@brief Main diagnostic method that takes care of collecting diagnostic data.
63-
* @param stat The stat param is what is the diagnostic tasks are added two. Internally published by the
64-
* diagnostic_updater package.
65-
* Added for diagnostics */
66-
void phidgetsDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat);
67-
6851
/**@brief Open a connection to a Phidget
6952
* @param serial_number The serial number of the phidget to which to attach (-1 will connect to any)*/
7053
int open(int serial_number);
@@ -111,10 +94,6 @@ class Phidget
11194

11295
private:
11396

114-
// Added for diagnostics
115-
bool is_error;
116-
int error_number;
117-
11897
static int AttachHandler(CPhidgetHandle handle, void *userptr);
11998
static int DetachHandler(CPhidgetHandle handle, void *userptr);
12099
static int ErrorHandler (CPhidgetHandle handle, void *userptr, int ErrorCode, const char *unknown);

phidgets_api/package.xml

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -17,10 +17,5 @@
1717
<author email="[email protected]">Copyright (C) 2010 Phidgets Inc. </author>
1818

1919
<buildtool_depend>catkin</buildtool_depend>
20-
<build_depend>diagnostics_updater</build_depend>
21-
<build_depend>diagnostics_msgs</build_depend>
22-
23-
<run_depend>diagnostics_updater</run_depend>
24-
<run_depend>diagnostics_msgs</run_depend>
2520

2621
</package>

phidgets_api/src/phidget.cpp

Lines changed: 1 addition & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -4,8 +4,6 @@ namespace phidgets {
44

55
Phidget::Phidget()
66
{
7-
updater.add("IMU Driver Status", this, &phidgets::Phidget::phidgetsDiagnostics);
8-
97
}
108

119
Phidget::~Phidget()
@@ -28,7 +26,6 @@ void Phidget::init(CPhidgetHandle handle)
2826

2927
int Phidget::open(int serial_number)
3028
{
31-
updater.setHardwareID("none");
3229
return CPhidget_open(handle_, serial_number);
3330
}
3431

@@ -97,23 +94,16 @@ std::string Phidget::getErrorDescription(int errorCode)
9794

9895
void Phidget::attachHandler()
9996
{
100-
is_connected = true;
101-
updater.force_update();
10297
printf("Phidget attached (serial# %d)\n", getDeviceSerialNumber());
10398
}
10499

105100
void Phidget::detachHandler()
106101
{
107-
printf("Phidget detached (serial# %d)\n", getDeviceSerialNumber());
108-
is_connected = false;
109-
updater.force_update();
102+
printf("Phidget detached (serial# %d)\n", getDeviceSerialNumber());
110103
}
111104

112105
void Phidget::errorHandler(int error)
113106
{
114-
is_error = true;
115-
updater.force_update();
116-
is_error = false;
117107
printf("Phidget error [%d]: %s\n", error, getErrorDescription(error).c_str());
118108
}
119109

@@ -135,27 +125,4 @@ int Phidget::ErrorHandler(CPhidgetHandle handle, void *userptr, int ErrorCode, c
135125
return 0;
136126
}
137127

138-
// Added for diagnostics
139-
void Phidget::phidgetsDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
140-
{
141-
if (is_connected)
142-
{
143-
stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "The Phidget is connected.");
144-
stat.add("Device Serial Number", getDeviceSerialNumber());
145-
stat.add("Device Name", getDeviceName());
146-
stat.add("Device Type", getDeviceType());
147-
}
148-
else
149-
{
150-
stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "The Phidget is not connected. Check USB.");
151-
}
152-
153-
if (is_error && error_number != 0)
154-
{
155-
stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "The Phidget is in Error.");
156-
stat.addf("Error Number","%f",error_number);
157-
stat.add("Error message",getErrorDescription(error_number));
158-
}
159-
}
160-
161128
} //namespace phidgets

phidgets_imu/CMakeLists.txt

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,12 @@
11
cmake_minimum_required(VERSION 2.8.3)
22
project(phidgets_imu)
33

4-
find_package(catkin REQUIRED COMPONENTS geometry_msgs nodelet phidgets_api roscpp sensor_msgs std_msgs std_srvs tf)
4+
find_package(catkin REQUIRED COMPONENTS geometry_msgs nodelet phidgets_api roscpp sensor_msgs std_msgs std_srvs tf diagnostic_msgs diagnostic_updater)
55

66
catkin_package(
77
INCLUDE_DIRS include
88
LIBRARIES phidgets_imu
9-
CATKIN_DEPENDS geometry_msgs nodelet phidgets_api roscpp sensor_msgs std_msgs std_srvs tf
9+
CATKIN_DEPENDS geometry_msgs nodelet phidgets_api roscpp sensor_msgs std_msgs std_srvs tf diagnostic_msgs diagnostic_updater
1010
)
1111

1212
include_directories(include ${catkin_INCLUDE_DIRS})

phidgets_imu/include/phidgets_imu/imu_ros_i.h

Lines changed: 22 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,11 +4,14 @@
44
#include <ros/ros.h>
55
#include <ros/service_server.h>
66
#include <boost/thread/mutex.hpp>
7+
#include <boost/shared_ptr.hpp>
78
#include <tf/transform_datatypes.h>
89
#include <sensor_msgs/Imu.h>
910
#include <std_srvs/Empty.h>
1011
#include <std_msgs/Bool.h>
1112
#include <geometry_msgs/Vector3Stamped.h>
13+
#include <diagnostic_updater/diagnostic_updater.h>
14+
#include <diagnostic_updater/publisher.h>
1215
#include <phidgets_api/imu.h>
1316

1417
using namespace std;
@@ -38,6 +41,16 @@ class ImuRosI : public Imu
3841
ros::Publisher cal_publisher_;
3942
ros::ServiceServer cal_srv_;
4043

44+
/**@brief updater object of class Update. Used to add diagnostic tasks, set ID etc. refer package API.
45+
* Added for diagnostics */
46+
diagnostic_updater::Updater diag_updater_;
47+
boost::shared_ptr<diagnostic_updater::TopicDiagnostic> imu_publisher_diag_ptr_;
48+
49+
// diagnostics
50+
bool is_connected;
51+
int error_number;
52+
double target_publish_freq_;
53+
4154
bool initialized_;
4255
boost::mutex mutex_;
4356
ros::Time last_imu_time_;
@@ -57,7 +70,16 @@ class ImuRosI : public Imu
5770
void calibrate();
5871
void initDevice();
5972
void dataHandler(CPhidgetSpatial_SpatialEventDataHandle* data, int count);
73+
void attachHandler();
74+
void detachHandler();
75+
void errorHandler(int error);
6076
void processImuData(CPhidgetSpatial_SpatialEventDataHandle* data, int i);
77+
78+
/**@brief Main diagnostic method that takes care of collecting diagnostic data.
79+
* @param stat The stat param is what is the diagnostic tasks are added two. Internally published by the
80+
* diagnostic_updater package.
81+
* Added for diagnostics */
82+
void phidgetsDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat);
6183
};
6284

6385
} //namespace phidgets

phidgets_imu/package.xml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,9 @@
2222
<build_depend>std_msgs</build_depend>
2323
<build_depend>std_srvs</build_depend>
2424
<build_depend>tf</build_depend>
25+
<build_depend>diagnostic_updater</build_depend>
26+
<build_depend>diagnostic_msgs</build_depend>
27+
2528
<run_depend>geometry_msgs</run_depend>
2629
<run_depend>nodelet</run_depend>
2730
<run_depend>phidgets_api</run_depend>
@@ -30,6 +33,8 @@
3033
<run_depend>std_msgs</run_depend>
3134
<run_depend>std_srvs</run_depend>
3235
<run_depend>tf</run_depend>
36+
<run_depend>diagnostic_updater</run_depend>
37+
<run_depend>diagnostic_msgs</run_depend>
3338

3439
<export>
3540
<nodelet plugin="${prefix}/phidgets_imu_nodelet.xml" />

phidgets_imu/src/imu_ros_i.cpp

Lines changed: 79 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,4 @@
1+
#include <boost/make_shared.hpp>
12
#include "phidgets_imu/imu_ros_i.h"
23

34
namespace phidgets {
@@ -6,6 +7,9 @@ ImuRosI::ImuRosI(ros::NodeHandle nh, ros::NodeHandle nh_private):
67
Imu(),
78
nh_(nh),
89
nh_private_(nh_private),
10+
is_connected(false),
11+
error_number(0),
12+
target_publish_freq_(0.0),
913
initialized_(false)
1014
{
1115
ROS_INFO ("Starting Phidgets IMU");
@@ -30,6 +34,20 @@ ImuRosI::ImuRosI(ros::NodeHandle nh, ros::NodeHandle nh_private):
3034
cal_publisher_ = nh_.advertise<std_msgs::Bool>(
3135
"imu/is_calibrated", 5);
3236

37+
// Set up the topic publisher diagnostics monitor for imu/data_raw
38+
// 1. The frequency status component monitors if imu data is published
39+
// within 10% tolerance of the desired frequency of 1.0 / period
40+
// 2. The timstamp status component monitors the delay between
41+
// the header.stamp of the imu message and the real (ros) time
42+
// the maximum tolerable drift is +- 100ms
43+
target_publish_freq_ = 1000.0 / static_cast<double>(period_);
44+
imu_publisher_diag_ptr_ = boost::make_shared<diagnostic_updater::TopicDiagnostic>(
45+
"imu/data_raw",
46+
boost::ref(diag_updater_),
47+
diagnostic_updater::FrequencyStatusParam(&target_publish_freq_, &target_publish_freq_, 0.1, 5),
48+
diagnostic_updater::TimeStampStatusParam(-0.1, 0.1)
49+
);
50+
3351
// **** advertise services
3452

3553
cal_srv_ = nh_.advertiseService(
@@ -61,6 +79,9 @@ ImuRosI::ImuRosI(ros::NodeHandle nh, ros::NodeHandle nh_private):
6179
}
6280
}
6381

82+
diag_updater_.setHardwareID("none");
83+
diag_updater_.add("IMU Driver Status", this, &phidgets::ImuRosI::phidgetsDiagnostics);
84+
6485
initDevice();
6586
}
6687

@@ -73,8 +94,9 @@ void ImuRosI::initDevice()
7394
int result = waitForAttachment(10000);
7495
if(result)
7596
{
76-
phidgets::Phidget::is_connected = false;
77-
phidgets::Phidget::updater.force_update();
97+
is_connected = false;
98+
error_number = result;
99+
diag_updater_.force_update();
78100
const char *err;
79101
CPhidget_getErrorDescription(result, &err);
80102
ROS_FATAL("Problem waiting for IMU attachment: %s Make sure the USB cable is connected and you have executed the phidgets_c_api/setup-udev.sh script.", err);
@@ -85,6 +107,11 @@ void ImuRosI::initDevice()
85107

86108
// calibrate on startup
87109
calibrate();
110+
111+
// set the hardware id for diagnostics
112+
diag_updater_.setHardwareIDf("%s-%d",
113+
getDeviceName().c_str(),
114+
getDeviceSerialNumber());
88115
}
89116

90117
bool ImuRosI::calibrateService(std_srvs::Empty::Request &req,
@@ -149,6 +176,7 @@ void ImuRosI::processImuData(CPhidgetSpatial_SpatialEventDataHandle* data, int i
149176
imu_msg->angular_velocity.z = data[i]->angularRate[2] * (M_PI / 180.0);
150177

151178
imu_publisher_.publish(imu_msg);
179+
imu_publisher_diag_ptr_->tick(time_now);
152180

153181
// **** create and publish magnetic field message
154182

@@ -174,6 +202,9 @@ void ImuRosI::processImuData(CPhidgetSpatial_SpatialEventDataHandle* data, int i
174202
}
175203

176204
mag_publisher_.publish(mag_msg);
205+
206+
// diagnostics
207+
diag_updater_.update();
177208
}
178209

179210
void ImuRosI::dataHandler(CPhidgetSpatial_SpatialEventDataHandle *data, int count)
@@ -182,5 +213,51 @@ void ImuRosI::dataHandler(CPhidgetSpatial_SpatialEventDataHandle *data, int coun
182213
processImuData(data, i);
183214
}
184215

216+
// Added for diagnostics
217+
void ImuRosI::attachHandler()
218+
{
219+
Imu::attachHandler();
220+
is_connected = true;
221+
// Reset error number to no error if the prev error was disconnect
222+
if (error_number == 13) error_number = 0;
223+
diag_updater_.force_update();
224+
}
225+
226+
void ImuRosI::detachHandler()
227+
{
228+
Imu::detachHandler();
229+
is_connected = false;
230+
diag_updater_.force_update();
231+
}
232+
233+
void ImuRosI::errorHandler(int error)
234+
{
235+
Imu::errorHandler(error);
236+
error_number = error;
237+
diag_updater_.force_update();
238+
}
239+
240+
void ImuRosI::phidgetsDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat)
241+
{
242+
if (is_connected)
243+
{
244+
stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "The Phidget is connected.");
245+
stat.add("Device Serial Number", getDeviceSerialNumber());
246+
stat.add("Device Name", getDeviceName());
247+
stat.add("Device Type", getDeviceType());
248+
}
249+
else
250+
{
251+
stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "The Phidget is not connected. Check the USB.");
252+
}
253+
254+
if (error_number != 0)
255+
{
256+
stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "The Phidget reports error.");
257+
stat.add("Error Number", error_number);
258+
stat.add("Error message", getErrorDescription(error_number));
259+
}
260+
}
261+
185262
} // namespace phidgets
186263

0 commit comments

Comments
 (0)