Skip to content

Commit 87a6e40

Browse files
committed
Fixing documentation warnings
1 parent 7b22aa9 commit 87a6e40

File tree

4 files changed

+9
-5
lines changed

4 files changed

+9
-5
lines changed

doc/state_estimation_nodes.rst

+1-1
Original file line numberDiff line numberDiff line change
@@ -98,7 +98,7 @@ For each of the sensor messages defined above, users must specify what variables
9898
9999
The order of the boolean values are :math:`X, Y, Z, roll, pitch, yaw, \dot{X}, \dot{Y}, \dot{Z}, \dot{roll}, \dot{pitch}, \dot{yaw}, \ddot{X}, \ddot{Y}, \ddot{Z}`. In this example, we are fusing :math:`X` and :math:`Y` position, :math:`yaw`, :math:`\dot{X}`, and :math:`\dot{yaw}`.
100100

101-
.. note:: The specification is done in the ``frame_id`` of the **sensor**, *not* in the ``world_frame`` or ``base_link_frame``. Please see the :doc:`sensor integration tutorial <sensor_integration_tutorial>` for more information.
101+
.. note:: The specification is done in the ``frame_id`` of the **sensor**, *not* in the ``world_frame`` or ``base_link_frame``. Please see the :doc:`coniguration tutorial <configuring_robot_localization>` for more information.
102102

103103
~[sensor]_queue_size
104104
^^^^^^^^^^^^^^^^^^^^

include/robot_localization/filter_utilities.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -61,7 +61,7 @@ namespace FilterUtilities
6161

6262
//! @brief Utility method for appending tf2 prefixes cleanly
6363
//! @param[in] tfPrefix - the tf2 prefix to append
64-
//! @paramp[in, out] frameId - the resulting frame_id value
64+
//! @param[in, out] frameId - the resulting frame_id value
6565
//!
6666
void appendPrefix(std::string tfPrefix, std::string &frameId);
6767

include/robot_localization/ros_filter.h

+6-3
Original file line numberDiff line numberDiff line change
@@ -227,9 +227,9 @@ template<class T> class RosFilter
227227
void setPoseCallback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg);
228228

229229
//! @brief Service callback for manually setting/resetting the internal pose estimate
230+
//!
230231
//! @param[in] request - Custom service request with pose information
231-
//! @param[out] response - N/A
232-
//! @return boolean true if successful, false if not
232+
//! @return true if successful, false if not
233233
bool setPoseSrvCallback(robot_localization::SetPose::Request& request,
234234
robot_localization::SetPose::Response&);
235235

@@ -252,14 +252,16 @@ template<class T> class RosFilter
252252
//!
253253
//! This method also inserts all measurements between the older filter timestamp and now into the measurements
254254
//! queue.
255+
//!
256+
//! @param[in] time - The time to which the filter state should revert
255257
//! @return True if restoring the filter succeeded. False if not.
256258
//!
257259
bool revertTo(const double time);
258260

259261
//! @brief Saves the current filter state in the queue of previous filter states
260262
//!
261263
//! These measurements will be used in backwards smoothing in the event that older measurements come in.
262-
//! @param[in] The filter base object whose state we want to save
264+
//! @param[in] filter - The filter base object whose state we want to save
263265
//!
264266
void saveFilterState(FilterBase &filter);
265267

@@ -272,6 +274,7 @@ template<class T> class RosFilter
272274
//! @param[in] errLevel - The error level of the diagnostic
273275
//! @param[in] topicAndClass - The sensor topic (if relevant) and class of diagnostic
274276
//! @param[in] message - Details of the diagnostic
277+
//! @param[in] staticDiag - Whether or not this diagnostic information is static
275278
//!
276279
void addDiagnostic(const int errLevel,
277280
const std::string &topicAndClass,

rosdoc.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -3,3 +3,4 @@
33
- builder: doxygen
44
output_dir: api
55
file_patterns: '*.cpp *.h *.dox *.md'
6+
exclude_patterns: '*/test/*'

0 commit comments

Comments
 (0)