robot_localization_listener_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2016, TNO IVS Helmond.
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
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  * 3. Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived
17  * from this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
26  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  */
32 
34 #include "robot_localization/GetState.h"
35 
36 #include <string>
37 
38 namespace RobotLocalization
39 {
40 
42 {
43 public:
45  {
47  }
48 
49  std::string getService()
50  {
51  return service_.getService();
52  }
53 
54 private:
58 
59  bool getStateCallback(robot_localization::GetState::Request &req,
60  robot_localization::GetState::Response &res)
61  {
62  Eigen::VectorXd state(STATE_SIZE);
63  Eigen::MatrixXd covariance(STATE_SIZE, STATE_SIZE);
64 
65  if ( !rll_.getState(req.time_stamp, req.frame_id, state, covariance) )
66  {
67  ROS_ERROR("Robot Localization Listener Node: Listener instance returned false at getState call.");
68  return false;
69  }
70 
71  for (size_t i = 0; i < STATE_SIZE; i++)
72  {
73  res.state[i] = (*(state.data() + i));
74  }
75 
76  for (size_t i = 0; i < STATE_SIZE * STATE_SIZE; i++)
77  {
78  res.covariance[i] = (*(covariance.data() + i));
79  }
80 
81  ROS_DEBUG("Robot Localization Listener Node: Listener responded with state and covariance at the requested time.");
82  return true;
83  }
84 };
85 
86 } // namespace RobotLocalization
87 
88 int main(int argc, char **argv)
89 {
90  ros::init(argc, argv, "robot_localization_listener_node");
91 
93  ROS_INFO_STREAM("Robot Localization Listener Node: Ready to handle GetState requests at " << rlln.getService());
94 
95  ros::spin();
96 
97  return 0;
98 }
const int STATE_SIZE
Global constants that define our state vector size and offsets to groups of values within that state...
Definition: filter_common.h:75
bool getState(const double time, const std::string &frame_id, Eigen::VectorXd &state, Eigen::MatrixXd &covariance, std::string world_frame_id="") const
Get a state from the localization estimator.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ROSCPP_DECL void spin(Spinner &spinner)
std::string getService() const
#define ROS_INFO_STREAM(args)
int main(int argc, char **argv)
#define ROS_ERROR(...)
bool getStateCallback(robot_localization::GetState::Request &req, robot_localization::GetState::Response &res)
#define ROS_DEBUG(...)


robot_localization
Author(s): Tom Moore
autogenerated on Wed Feb 3 2021 03:34:02