ukf_localization_node.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014, 2015, 2016, Charles River Analytics, Inc.
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 
35 #include <ros/ros.h>
36 
37 #include <vector>
38 
39 int main(int argc, char **argv)
40 {
41  ros::init(argc, argv, "ukf_navigation_node");
42  ros::NodeHandle nhLocal("~");
43 
44  std::vector<double> args(3, 0);
45 
46  nhLocal.param("alpha", args[0], 0.001);
47  nhLocal.param("kappa", args[1], 0.0);
48  nhLocal.param("beta", args[2], 2.0);
49 
50  RobotLocalization::RosUkf ukf(args);
51 
52  ukf.run();
53 
54  return EXIT_SUCCESS;
55 }
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
int main(int argc, char **argv)
void run()
Main run method.


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