8 #include <sensor_msgs/NavSatStatus.h> 9 #include <sensor_msgs/NavSatFix.h> 11 #include <nav_msgs/Odometry.h> 20 void callback(
const sensor_msgs::NavSatFixConstPtr& fix) {
21 if (fix->status.status == sensor_msgs::NavSatStatus::STATUS_NO_FIX) {
30 double northing, easting;
33 LLtoUTM(fix->latitude, fix->longitude, northing, easting, zone);
36 nav_msgs::Odometry odom;
37 odom.header.stamp = fix->header.stamp;
41 odom.header.frame_id = fix->header.frame_id +
"/utm_" + zone;
43 odom.header.frame_id = fix->header.frame_id;
47 odom.header.frame_id =
frame_id +
"/utm_" + zone;
55 odom.pose.pose.position.x = easting;
56 odom.pose.pose.position.y = northing;
57 odom.pose.pose.position.z = fix->altitude;
59 odom.pose.pose.orientation.x = 0;
60 odom.pose.pose.orientation.y = 0;
61 odom.pose.pose.orientation.z = 0;
62 odom.pose.pose.orientation.w = 1;
65 boost::array<double, 36> covariance = {{
66 fix->position_covariance[0],
67 fix->position_covariance[1],
68 fix->position_covariance[2],
70 fix->position_covariance[3],
71 fix->position_covariance[4],
72 fix->position_covariance[5],
74 fix->position_covariance[6],
75 fix->position_covariance[7],
76 fix->position_covariance[8],
80 0, 0, 0, 0, 0, rot_cov
83 odom.pose.covariance = covariance;
89 int main (
int argc,
char **argv) {
90 ros::init(argc, argv,
"utm_odometry_node");
96 priv_node.
param<
double>(
"rot_covariance",
rot_cov, 99999.0);
99 odom_pub = node.
advertise<nav_msgs::Odometry>(
"odom", 10);
static ros::Publisher odom_pub
void publish(const boost::shared_ptr< M > &message) const
#define ROS_DEBUG_THROTTLE(rate,...)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string child_frame_id
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
static void LLtoUTM(const double Lat, const double Long, double &UTMNorthing, double &UTMEasting, char *UTMZone)
int main(int argc, char **argv)
Universal Transverse Mercator transforms.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void callback(const sensor_msgs::NavSatFixConstPtr &fix)