예제 #1
0
class Declination:
    def __init__(self):
        self.gm = GeoMag("../src/geomag/WMM.COF")
        rospy.init_node("declination_provider")

        self.fix = None
        self.declination = 0.0
        self.sub = rospy.Subscriber("fix", NavSatFix, self._fix)
        self.pub = rospy.Publisher("declination", Float32, latch=True)

    def _fix(self, msg):
        #if self.fix:
        #    # For now, return. Later, figure out conditions under which to recompute.
        #    return

        if msg.latitude and msg.longitude:
            self.fix = msg
            if not msg.altitude:
                msg.altitude = 0
            result = self.gm.calc(msg.latitude, msg.longitude, msg.altitude)
            if self.declination != result.dec:
                self.pub.publish(radians(result.dec))
                self.declination = result.dec

    def spin(self):
        rospy.spin()
예제 #2
0
class Compute:
    def __init__(self):
        rospy.init_node("declination_provider")
        wmm_path = path.join(get_pkg_dir('declination'), "wmm", "WMM.COF")
        self.gm = GeoMag(wmm_path)

        self.fix = None
        self.sub = rospy.Subscriber("fix", NavSatFix, self._fix)
        self.pub = rospy.Publisher("declination", Float32, latch=True)

    def _fix(self, msg):
        if self.fix:
            # For now, return. Later, figure out conditions under which to recompute.
            return

        if msg.latitude and msg.longitude:
            self.fix = msg
            if not msg.altitude: msg.altitude = 0
            result = self.gm.calc(msg.latitude, msg.longitude, msg.altitude)
            result_rad = radians(result.dec)
            self.pub.publish(result_rad) 
            rospy.loginfo("Computed magnetic declination to be %f rad (%f degrees)" \
                % (result_rad, result.dec))

    def spin(self):
        rospy.spin()
예제 #3
0
class Declination:
    def __init__(self):
        self.gm = GeoMag("../src/geomag/WMM.COF")
        rospy.init_node("declination_provider")

        self.fix = None
        self.sub = rospy.Subscriber("fix", NavSatFix, self._fix)
        self.pub = rospy.Publisher("declination", Float32, latch=True)

    def _fix(msg):
        if self.fix:
            # For now, return. Later, figure out conditions under which to recompute.
            return

        if msg.latitude and msg.longitude:
            self.fix = msg
            if not msg.altitude: msg.altitude = 0
            result = self.gm.calc(msg.latitude, msg.longitude, msg.altitude)
            self.pub.publish(result.dec) 

    def spin(self):
        rospy.spin()
예제 #4
0
#!/usr/bin/python

import roslib
roslib.load_manifest('lrm_outdoor')
import rospy
from geomag.geomag import GeoMag

if __name__ == "__main__":
    rospy.init_node("test_declination")
    gm = GeoMag("../src/geomag/WMM.COF")
    #mag = gm.calc(43.411454, -80.472708)
    mag = gm.calc(-22.411454, -44.472708)
    print mag.dec