Skip to content

Commit

Permalink
Merge pull request #41 from ethz-asl/feature/jenkins
Browse files Browse the repository at this point in the history
Feature/jenkins
  • Loading branch information
marco-tranzatto authored May 30, 2018
2 parents b3b6647 + 401e37e commit 831abaa
Show file tree
Hide file tree
Showing 26 changed files with 140 additions and 68 deletions.
4 changes: 4 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,10 @@ License
-------
The source code is released under a [BSD 3-Clause license](https://github.com/ethz-asl/ethz_piksi_ros/blob/master/LICENSE).

Build Status
-------
[![Build Status](https://ci.leggedrobotics.com/buildStatus/icon?job=github_ethz-asl/ethz_piksi_ros/master)](https://ci.leggedrobotics.com/job/github_ethz-asl/job/ethz_piksi_ros/job/master/)

Credits
-------
Marco Tranzatto, Kai Holtmann, Michael Pantic - ETHZ ASL & RSL - 30 November 2017
Expand Down
2 changes: 1 addition & 1 deletion ethz_piksi_ros/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>ethz_piksi_ros</name>
<version>1.5.0</version>
<version>1.6.0</version>
<description>Meta-package for the ethz_piksi_ros repository.</description>

<maintainer email="[email protected]">Marco Tranzatto</maintainer>
Expand Down
2 changes: 2 additions & 0 deletions jenkins-pipeline
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
library 'continuous_integration_pipeline'
ciPipeline("--ignore ethz_piksi_ros piksi_v2_rtk_ros rqt_gps_rtk_plugin utils")
27 changes: 23 additions & 4 deletions piksi_multi_rtk_ros/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,11 @@ project(piksi_multi_rtk_ros)
## Find catkin macros and libraries
find_package(catkin REQUIRED
COMPONENTS
rospy
geometry_msgs
piksi_rtk_msgs
sensor_msgs
geometry_msgs
roslib
rospy
)

###################################
Expand All @@ -23,8 +24,26 @@ catkin_package(
# INCLUDE_DIRS
# LIBRARIES
CATKIN_DEPENDS
piksi_rtk_msgs
sensor_msgs
geometry_msgs
sensor_msgs
piksi_rtk_msgs
roslib
rospy
# DEPENDS
)

## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
catkin_python_setup()

#############
## Install ##
#############
catkin_install_python(PROGRAMS bin/piksi_multi bin/geodetic_survey
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

install(DIRECTORY cfg launch log_surveys rosbag_record_scripts
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
6 changes: 6 additions & 0 deletions piksi_multi_rtk_ros/bin/geodetic_survey
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
#! /usr/bin/env python

from piksi_multi_rtk_ros import GeodeticSurvey

if __name__ == '__main__':
geodetic_survey = GeodeticSurvey()
6 changes: 6 additions & 0 deletions piksi_multi_rtk_ros/bin/piksi_multi
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
#! /usr/bin/env python

from piksi_multi_rtk_ros import PiksiMulti

if __name__ == '__main__':
piksi_multi = PiksiMulti()
2 changes: 1 addition & 1 deletion piksi_multi_rtk_ros/launch/geodetic_survey.launch
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
<include file="$(find piksi_multi_rtk_ros)/launch/piksi_multi_base_station.launch"/>

<!-- Geodetic Survey. -->
<node pkg="piksi_multi_rtk_ros" type="geodetic_survey.py" name="geodetic_survey" output="screen">
<node pkg="piksi_multi_rtk_ros" type="geodetic_survey" name="geodetic_survey" output="screen">
<param name="number_of_desired_fixes" value="$(arg number_of_desired_fixes)"/>
<param name="height_base_station_from_ground" value="$(arg height_base_station_from_ground)"/>
</node>
Expand Down
2 changes: 1 addition & 1 deletion piksi_multi_rtk_ros/launch/piksi_multi_base_station.launch
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
<arg name="broadcast_addr" default="192.168.0.255"/>

<!-- Piksi Multi ROS driver node: base station mode -->
<node pkg="piksi_multi_rtk_ros" type="piksi_multi.py" name="piksi_multi_base_station" output="screen" respawn="true">
<node pkg="piksi_multi_rtk_ros" type="piksi_multi" name="piksi_multi_base_station" output="screen" respawn="true">
<!-- Load default settings -->
<rosparam file="$(find piksi_multi_rtk_ros)/cfg/piksi_multi_driver_settings.yaml"/>

Expand Down
2 changes: 1 addition & 1 deletion piksi_multi_rtk_ros/launch/piksi_multi_rover.launch
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
<arg name="enu_origin_file" default="$(find piksi_multi_rtk_ros)/cfg/enu_origin_example.yaml"/>

<!-- Piksi Multi ROS driver node: rover mode -->
<node pkg="piksi_multi_rtk_ros" type="piksi_multi.py" name="piksi" output="screen" respawn="true">
<node pkg="piksi_multi_rtk_ros" type="piksi_multi" name="piksi" output="screen" respawn="true">
<!-- Load default settings -->
<rosparam file="$(find piksi_multi_rtk_ros)/cfg/piksi_multi_driver_settings.yaml"/>

Expand Down
7 changes: 4 additions & 3 deletions piksi_multi_rtk_ros/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>piksi_multi_rtk_ros</name>
<version>1.5.0</version>
<version>1.6.0</version>
<description>
ROS driver for Piksi Multi RTK GPS Receiver.
</description>
Expand All @@ -15,9 +15,10 @@

<buildtool_depend>catkin</buildtool_depend>

<depend>rospy</depend>
<depend>geometry_msgs</depend>
<depend>piksi_rtk_msgs</depend>
<depend>sensor_msgs</depend>
<depend>geometry_msgs</depend>
<depend>roslib</depend>
<depend>rospy</depend>

</package>
12 changes: 12 additions & 0 deletions piksi_multi_rtk_ros/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
## ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD

from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup

# fetch values from package.xml
setup_args = generate_distutils_setup(
packages=['piksi_multi_rtk_ros'],
scripts=['bin/geodetic_survey', 'bin/piksi_multi'],
package_dir={'': 'src'})

setup(**setup_args)
File renamed without changes.
3 changes: 3 additions & 0 deletions piksi_multi_rtk_ros/src/piksi_multi_rtk_ros/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
from piksi_multi import PiksiMulti
from geodetic_survey import GeodeticSurvey

Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#

import rospy
import roslib.packages
from piksi_rtk_msgs.srv import *
import std_srvs.srv
from sensor_msgs.msg import (NavSatFix, NavSatStatus)
Expand All @@ -14,11 +15,13 @@


class GeodeticSurvey:
kRosPackageName = "piksi_multi_rtk_ros"
kServiceTimeOutSeconds = 10.0
kWaitBetweenReadReqAndResSeconds = 1.0
kRelativeTolleranceGeodeticComparison = 1e-10

def __init__(self):
rospy.init_node('geodetic_survey')
rospy.loginfo(rospy.get_name() + " start")

self.latitude_accumulator = 0.0
Expand Down Expand Up @@ -74,7 +77,7 @@ def navsatfix_callback(self, msg):
rospy.loginfo(
"Creating ENU frame on surveyed position and substructing specified height of base station.")
self.log_enu_origin_position(lat0, lon0, alt0)
rospy.signal_shutdown("Base station position set correctly.")
rospy.signal_shutdown("Base station position set correctly. Stop this node and launch base station node.")
else:
rospy.logerr("Base station position not set correctly.")
rospy.signal_shutdown("Base station position not set correctly.")
Expand Down Expand Up @@ -188,22 +191,22 @@ def read_settings_from_piksi(self, section_setting, setting):
return False, -1

def log_surveyed_position(self, lat0, lon0, alt0):
# current path of geodetic_survey.py file
script_path = os.path.dirname(os.path.realpath(sys.argv[0]))
now = time.strftime("%Y_%m_%d_%H_%M_%S")
desired_path = "%s/../log_surveys/base_station_survey_%s.txt" % (script_path, now)
now = time.strftime("%Y-%m-%d-%H-%M-%S")
package_path = roslib.packages.get_pkg_dir(self.kRosPackageName)
desired_path = "%s/log_surveys/base_station_survey_%s.txt" % (package_path, now)
file_obj = open(desired_path, 'w')
file_obj.write("# File automatically generated on %s\n\n" % now)
file_obj.write("latitude0_deg: %.10f\n" % lat0)
file_obj.write("longitude0_deg: %.10f\n" % lon0)
file_obj.write("altitude0: %.2f\n" % alt0)
file_obj.close()
rospy.loginfo("Surveyed position saved in \'" + desired_path + "\'")

def log_enu_origin_position(self, lat0, lon0, alt0):
# current path of geodetic_survey.py file
script_path = os.path.dirname(os.path.realpath(sys.argv[0]))
now = time.strftime("%Y_%m_%d_%H_%M_%S")
desired_path = "%s/../log_surveys/enu_origin_%s.txt" % (script_path, now)
now = time.strftime("%Y-%m-%d-%H-%M-%S")
package_path = roslib.packages.get_pkg_dir(self.kRosPackageName)
desired_path = "%s/log_surveys/enu_origin_%s.txt" % (package_path, now)
file_obj = open(desired_path, 'w')
file_obj.write("# File automatically generated on %s\n" % now)
file_obj.write(
Expand All @@ -212,18 +215,8 @@ def log_enu_origin_position(self, lat0, lon0, alt0):
file_obj.write("longitude0_deg: %.10f\n" % lon0)
file_obj.write("altitude0: %.2f\n" % (alt0 - self.height_base_station_from_ground))
file_obj.close()
rospy.loginfo("ENU origin saved in \'" + desired_path + "\'")

# https://www.python.org/dev/peps/pep-0485/#proposed-implementation
def is_close(self, a, b, rel_tol=1e-09, abs_tol=0.0):
return abs(a - b) <= max(rel_tol * max(abs(a), abs(b)), abs_tol)


# Main function.
if __name__ == '__main__':
rospy.init_node('geodetic_survey')

# Go to class functions that do all the heavy lifting. Do error checking.
try:
geodetic_survey = GeodeticSurvey()
except rospy.ROSInterruptException:
pass
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@ class PiksiMulti:
def __init__(self):

# Print info.
rospy.init_node('piksi')
rospy.sleep(0.5) # Wait for a while for init to complete before printing.
rospy.loginfo(rospy.get_name() + " start")

Expand Down Expand Up @@ -1124,14 +1125,3 @@ def clear_last_setting_read(self):
self.last_section_setting_read = []
self.last_setting_read = []
self.last_value_read = []


# Main function.
if __name__ == '__main__':
rospy.init_node('piksi')

# Go to class functions that do all the heavy lifting. Do error checking.
try:
piksi_multi = PiksiMulti()
except rospy.ROSInterruptException:
pass
2 changes: 2 additions & 0 deletions piksi_rtk_kml/.gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
# KML files
kml/*
25 changes: 22 additions & 3 deletions piksi_rtk_kml/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,10 @@ project(piksi_rtk_kml)
## Find catkin macros and libraries
find_package(catkin REQUIRED
COMPONENTS
rospy
piksi_rtk_msgs
geometry_msgs
piksi_rtk_msgs
roslib
rospy
)

###################################
Expand All @@ -22,7 +23,25 @@ catkin_package(
# INCLUDE_DIRS
# LIBRARIES
CATKIN_DEPENDS
piksi_rtk_msgs
geometry_msgs
piksi_rtk_msgs
roslib
rospy
# DEPENDS
)

## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
catkin_python_setup()

#############
## Install ##
#############
catkin_install_python(PROGRAMS bin/piksi_rtk_kml
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

install(DIRECTORY cfg launch kml
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)
7 changes: 7 additions & 0 deletions piksi_rtk_kml/bin/piksi_rtk_kml
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
#! /usr/bin/env python

from piksi_rtk_kml import PiksiRtkKml

# Main function.
if __name__ == '__main__':
piksi_rtk_kml = PiksiRtkKml()
6 changes: 4 additions & 2 deletions piksi_rtk_kml/launch/piksi_rtk_kml.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,11 +2,13 @@

<launch>

<node pkg="piksi_rtk_kml" type="piksi_rtk_kml.py" name="piksi_rtk_kml" output="screen">
<!-- Node to convert Piksi ROS driver output to KML format -->
<node pkg="piksi_rtk_kml" type="piksi_rtk_kml" name="piksi_rtk_kml" output="screen">
<!-- Load default settings -->
<rosparam file="$(find piksi_rtk_kml)/cfg/piksi_rtk_kml_settings.yaml"/>
</node>

<node pkg="piksi_multi_rtk_gps" type="piksi_multi.py" name="piksi" output="screen"/>
<!-- ROS node to read Piksi Multi output -->
<node pkg="piksi_multi_rtk_ros" type="piksi_multi" name="piksi" output="screen"/>

</launch>
7 changes: 4 additions & 3 deletions piksi_rtk_kml/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>piksi_rtk_kml</name>
<version>1.5.0</version>
<version>1.6.0</version>
<description>
ROS node to write KML file from Piksi messages.
</description>
Expand All @@ -13,8 +13,9 @@

<buildtool_depend>catkin</buildtool_depend>

<depend>rospy</depend>
<depend>piksi_rtk_msgs</depend>
<depend>geometry_msgs</depend>
<depend>piksi_rtk_msgs</depend>
<depend>roslib</depend>
<depend>rospy</depend>

</package>
12 changes: 12 additions & 0 deletions piksi_rtk_kml/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
## ! DO NOT MANUALLY INVOKE THIS setup.py, USE CATKIN INSTEAD

from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup

# fetch values from package.xml
setup_args = generate_distutils_setup(
packages=['piksi_rtk_kml'],
scripts=['bin/piksi_rtk_kml'],
package_dir={'': 'src'})

setup(**setup_args)
1 change: 1 addition & 0 deletions piksi_rtk_kml/src/piksi_rtk_kml/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
from piksi_rtk_kml import PiksiRtkKml
Loading

0 comments on commit 831abaa

Please sign in to comment.