graft_ukf_absolute.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, 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 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 Willow Garage, Inc. 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 /*
31  * Author: Chad Rockey
32  */
33 
34 #include <iostream>
35 #include <Eigen/Dense>
36 #include <ros/ros.h>
38 #include <graft/GraftSensor.h>
40 #include <graft/GraftImuTopic.h>
41 #include <graft/GraftUKFAbsolute.h>
42 #include <graft/GraftState.h>
44 
46 
49 
50 nav_msgs::Odometry odom_;
51 
52 // tf
55 
56 std::string parent_frame_id_;
57 std::string child_frame_id_;
58 
59 void publishTF(const nav_msgs::Odometry& msg){
60  geometry_msgs::TransformStamped tf;
61  tf.header.stamp = msg.header.stamp;
62  tf.header.frame_id = msg.header.frame_id;
63  tf.child_frame_id = msg.child_frame_id;
64 
65  tf.transform.translation.x = msg.pose.pose.position.x;
66  tf.transform.translation.y = msg.pose.pose.position.y;
67  tf.transform.translation.z = msg.pose.pose.position.z;
68  tf.transform.rotation = msg.pose.pose.orientation;
69 
70  broadcaster_->sendTransform(tf);
71 }
72 
73 void timer_callback(const ros::TimerEvent& event){
74  double dt = ukfv.predictAndUpdate();
75 
76  graft::GraftState state = *ukfv.getMessageFromState();
77  state.header.stamp = ros::Time::now();
78  state_pub.publish(state);
79 
80  // Update Odometry
81  odom_.header.stamp = ros::Time::now();
82  odom_.header.frame_id = parent_frame_id_;
83  odom_.child_frame_id = child_frame_id_;
84  odom_.pose.pose = state.pose;
85  odom_.twist.twist = state.twist;
87  if(publish_tf_){
89  }
90 }
91 
92 int main(int argc, char **argv)
93 {
94  ros::init(argc, argv, "graft_ukf_velocity");
96  ros::NodeHandle pnh("~");
97  state_pub = pnh.advertise<graft::GraftState>("state", 5);
98  odom_pub = n.advertise<nav_msgs::Odometry>("odom_combined", 5);
99 
100  // Load parameters
101  std::vector<boost::shared_ptr<GraftSensor> > topics;
102  std::vector<ros::Subscriber> subs;
103  GraftParameterManager manager(n, pnh);
104  manager.loadParameters(topics, subs);
105 
106  publish_tf_ = manager.getPublishTF();
107 
109  child_frame_id_ = manager.getChildFrameID();
110 
111  // Set up the E
112  std::vector<double> initial_covariance = manager.getInitialCovariance();
113  std::vector<double> Q = manager.getProcessNoise();
114  ukfv.setAlpha(manager.getAlpha());
115  ukfv.setKappa(manager.getKappa());
116  ukfv.setBeta(manager.getBeta());
117  ukfv.setInitialCovariance(initial_covariance);
119  ukfv.setTopics(topics);
120 
121  odom_.pose.pose.position.x = 0.0;
122  odom_.pose.pose.position.y = 0.0;
123  odom_.pose.pose.position.z = 0.0;
124 
125  odom_.pose.pose.orientation.w = 1.0;
126  odom_.pose.pose.orientation.x = 0.0;
127  odom_.pose.pose.orientation.y = 0.0;
128  odom_.pose.pose.orientation.z = 0.0;
129 
130  odom_.twist.twist.linear.x = 0.0;
131  odom_.twist.twist.linear.y = 0.0;
132  odom_.twist.twist.linear.z = 0.0;
133  odom_.twist.twist.angular.x = 0.0;
134  odom_.twist.twist.angular.y = 0.0;
135  odom_.twist.twist.angular.z = 0.0;
136 
137  // Tf Broadcaster
139 
140  // Start loop
142 
143  // Spin
144  ros::spin();
145 }
GraftParameterManager::getChildFrameID
std::string getChildFrameID()
Definition: GraftParameterManager.cpp:338
state_pub
ros::Publisher state_pub
Definition: graft_ukf_absolute.cpp:47
GraftParameterManager::getBeta
double getBeta()
Definition: GraftParameterManager.cpp:404
ukfv
GraftUKFAbsolute ukfv
Definition: graft_ukf_absolute.cpp:45
ros::Publisher
boost::shared_ptr
GraftParameterManager::getInitialCovariance
std::vector< double > getInitialCovariance()
Definition: GraftParameterManager.cpp:380
GraftUKFAbsolute::setAlpha
void setAlpha(const double alpha)
Definition: GraftUKFAbsolute.cpp:451
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
GraftUKFAbsolute::setBeta
void setBeta(const double beta)
Definition: GraftUKFAbsolute.cpp:459
GraftParameterManager.h
ros.h
GraftUKFAbsolute::setTopics
void setTopics(std::vector< boost::shared_ptr< GraftSensor > > &topics)
Definition: GraftUKFAbsolute.cpp:411
GraftParameterManager::loadParameters
void loadParameters(std::vector< boost::shared_ptr< GraftSensor > > &topics, std::vector< ros::Subscriber > &subs)
Definition: GraftParameterManager.cpp:163
GraftParameterManager::getPublishTF
bool getPublishTF()
Definition: GraftParameterManager.cpp:374
GraftUKFAbsolute::setProcessNoise
void setProcessNoise(std::vector< double > &Q)
Definition: GraftUKFAbsolute.cpp:433
GraftUKFAbsolute::getMessageFromState
graft::GraftStatePtr getMessageFromState()
Definition: GraftUKFAbsolute.cpp:214
GraftParameterManager::getAlpha
double getAlpha()
Definition: GraftParameterManager.cpp:392
publishTF
void publishTF(const nav_msgs::Odometry &msg)
Definition: graft_ukf_absolute.cpp:59
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
GraftParameterManager
Definition: GraftParameterManager.h:43
transform_broadcaster.h
child_frame_id_
std::string child_frame_id_
Definition: graft_ukf_absolute.cpp:57
GraftUKFAbsolute
Definition: GraftUKFAbsolute.h:51
GraftImuTopic.h
GraftSensor.h
publish_tf_
bool publish_tf_
Definition: graft_ukf_absolute.cpp:53
tf::TransformBroadcaster
parent_frame_id_
std::string parent_frame_id_
Definition: graft_ukf_absolute.cpp:56
GraftOdometryTopic.h
ros::TimerEvent
GraftUKFAbsolute::setInitialCovariance
void setInitialCovariance(std::vector< double > &P)
Definition: GraftUKFAbsolute.cpp:415
GraftParameterManager::getProcessNoise
std::vector< double > getProcessNoise()
Definition: GraftParameterManager.cpp:386
main
int main(int argc, char **argv)
Definition: graft_ukf_absolute.cpp:92
GraftParameterManager::getKappa
double getKappa()
Definition: GraftParameterManager.cpp:398
broadcaster_
boost::shared_ptr< tf::TransformBroadcaster > broadcaster_
Definition: graft_ukf_absolute.cpp:54
GraftParameterManager::getUpdateRate
double getUpdateRate()
Definition: GraftParameterManager.cpp:344
GraftUKFAbsolute::predictAndUpdate
double predictAndUpdate()
Definition: GraftUKFAbsolute.cpp:370
odom_
nav_msgs::Odometry odom_
Definition: graft_ukf_absolute.cpp:50
GraftUKFAbsolute::setKappa
void setKappa(const double kappa)
Definition: GraftUKFAbsolute.cpp:455
ros::spin
ROSCPP_DECL void spin()
tf
odom_pub
ros::Publisher odom_pub
Definition: graft_ukf_absolute.cpp:48
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::Timer
timer_callback
void timer_callback(const ros::TimerEvent &event)
Definition: graft_ukf_absolute.cpp:73
ros::NodeHandle
GraftParameterManager::getParentFrameID
std::string getParentFrameID()
Definition: GraftParameterManager.cpp:332
ros::Time::now
static Time now()
GraftUKFAbsolute.h


graft
Author(s): Chad Rockey
autogenerated on Wed Mar 2 2022 00:20:33