Skip to content
Snippets Groups Projects
Commit a4bc7e9e authored by Boulongne Corentin's avatar Boulongne Corentin
Browse files

Added first version of ros-chrony node

parent 4956f23a
No related branches found
No related tags found
No related merge requests found
cmake_minimum_required(VERSION 3.0.2)
project(ros_chrony)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
message_generation
std_msgs
)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
## 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()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
add_message_files(
FILES
ClockInfo.msg
ClockList.msg
)
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
std_msgs # Or other packages containing msgs
)
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES clock_sync_gps
CATKIN_DEPENDS roscpp rospy message_runtime std_msgs
# DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
${catkin_INCLUDE_DIRS}
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/clock_sync_gps.cpp
# )
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
add_executable(${PROJECT_NAME}_node src/ros-chrony-interface.cpp)
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
target_link_libraries(${PROJECT_NAME}_node
${catkin_LIBRARIES}
)
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# catkin_install_python(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_clock_sync_gps.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
Header header
string name
string mode
string state
duration adjusted_offset
duration measured_offset
duration estimated_error
#string raw_data
Header header
ClockInfo[] list
string raw_data
\ No newline at end of file
<?xml version="1.0"?>
<package format="2">
<name>ros_chrony</name>
<version>1.0.0</version>
<description>The ros-chrony package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="cristal@todo.todo">cristal</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/clock_sync_gps</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>message_generation</build_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>message_runtime</exec_depend>
<depend>std_msgs</depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>
#include <stdio.h>
#include <stdlib.h>
#include <ros/ros.h>
#include <iostream>
#include <boost/algorithm/string.hpp>
#include <vector>
#include "clock_sync_gps/ClockInfo.h"
#include "clock_sync_gps/ClockList.h"
int main( int argc, char *argv[] )
{
int freq;
ros::init(argc, argv, "ros_chrony_interface");
ros::NodeHandle nh;
ros::param::param<int>("~freq", freq, 5);
ros::Publisher pubGPSClock = nh.advertise<clock_sync_gps::ClockInfo>("/clock_gps", 1000);
ros::Publisher pubPPSClock = nh.advertise<clock_sync_gps::ClockInfo>("/clock_pps", 1000);
ros::Publisher pubListClock = nh.advertise<clock_sync_gps::ClockList>("/clock_list", 1000);
ROS_INFO("RATE IS : %d", freq);
ros::Rate rate(freq);
FILE *fp;
char path[1035];
std::string gps_;
std::string pps_;
std::string mode_, state_;
int pos_sign_1, pos_sign_2, pos_sign_3, pos_state, pos_name;
int pos_sign_1_pps, pos_sign_2_pps, pos_sign_3_pps;
clock_sync_gps::ClockInfo msgClockInfo_gps = clock_sync_gps::ClockInfo();
clock_sync_gps::ClockInfo msgClockInfo_pps = clock_sync_gps::ClockInfo();
clock_sync_gps::ClockList msgClockList = clock_sync_gps::ClockList();
ros::Duration t1_gps(0);
ros::Duration t2_gps(0);
ros::Duration t3_gps(0);
ros::Duration t1_pps(0);
ros::Duration t2_pps(0);
ros::Duration t3_pps(0);
while(ros::ok()){
// Open the command for reading.
fp = popen("chronyc sources | grep ^#" , "r");
if (fp == NULL) {
printf("Failed to run command\n" );
exit(1);
}
// Read the output a line at a time - output it.
while (fgets(path, sizeof(path), fp) != NULL) {
if(boost::algorithm::contains(path, "GPS")){
gps_ = path;
}else if(boost::algorithm::contains(path, "PPS")){
pps_ = path;
}
}
boost::algorithm::erase_all(gps_, " ");
boost::algorithm::erase_all(pps_, " ");
//building msg for GPS
pos_sign_1 = gps_.find_first_of("+-", 2); // ignoring start of string #- or #+ to get first measure
pos_sign_2 = gps_.find_first_of("+-", pos_sign_1+1); // from 1st sign detected find next
pos_sign_3 = gps_.find_first_of("/");
t1_gps.nsec = std::stoi(gps_.substr(pos_sign_1, (pos_sign_2-pos_sign_1)-1));
t2_gps.nsec = std::stoi(gps_.substr(pos_sign_2, (pos_sign_3 - pos_sign_2)-1));
t3_gps.nsec = std::stoi(gps_.substr(pos_sign_3+2, gps_.find('\n')-pos_sign_3-2)); //
switch(gps_.at(0)){
case '#':
msgClockInfo_gps.mode = "Local Clock";
break;
case '^':
msgClockInfo_gps.mode = "Server";
break;
case '=':
msgClockInfo_gps.mode = "Peer";
break;
default:
msgClockInfo_gps.mode = "Error while retreiving mode";
break;
}
switch(gps_.at(1)){
case '*':
msgClockInfo_gps.state = "Current best";
break;
case '+':
msgClockInfo_gps.state = "Combined";
break;
case '-':
msgClockInfo_gps.state = "Not Combined";
break;
case 'x':
msgClockInfo_gps.state = "May be in error";
break;
case '~':
msgClockInfo_gps.state = "Too variable";
break;
case '?':
msgClockInfo_gps.state = "Unusable";
break;
default:
msgClockInfo_gps.state = "Error while retreiving mode";
break;
}
msgClockInfo_gps.name = gps_.substr(2,3);
//msgClockInfo_gps.mode = gps_.substr(0,1); -> switch case
//msgClockInfo_gps.state = gps_.substr(1,1); -> switch case
msgClockInfo_gps.adjusted_offset = t1_gps; // substring to send data from 1st sign
msgClockInfo_gps.measured_offset = t2_gps; // substring to send data from 2nd sign
msgClockInfo_gps.estimated_error = t3_gps; // substring to send data from last sign
//Building msg for PPS
pos_sign_1_pps = pps_.find_first_of("+-", 2); // ignoring start of string #- or #+ to get first measure
pos_sign_2_pps = pps_.find_first_of("+-", pos_sign_1_pps+1); // from 1st sign detected find next
pos_sign_3_pps = pps_.find_first_of("/"); // from 2nd sign detected find next (last)
t1_pps.nsec = std::stoi(pps_.substr(pos_sign_1_pps, (pos_sign_2_pps-pos_sign_1_pps)-1));
t2_pps.nsec = std::stoi(pps_.substr(pos_sign_2_pps, (pos_sign_3_pps - pos_sign_2_pps)-1));
t3_pps.nsec = std::stoi(pps_.substr(pos_sign_3_pps+2, pps_.find('\n')-pos_sign_3_pps-2)); // errr ?
switch(pps_.at(0)){
case '#':
msgClockInfo_pps.mode = "Local Clock";
break;
case '^':
msgClockInfo_pps.mode = "Server";
break;
case '=':
msgClockInfo_pps.mode = "Peer";
break;
default:
msgClockInfo_pps.mode = "Error while retreiving mode";
break;
}
switch(pps_.at(1)){
case '*':
msgClockInfo_pps.state = "Current best";
break;
case '+':
msgClockInfo_pps.state = "Combined";
break;
case '-':
msgClockInfo_pps.state = "Not Combined";
break;
case 'x':
msgClockInfo_pps.state = "May be in error";
break;
case '~':
msgClockInfo_pps.state = "Too variable";
break;
case '?':
msgClockInfo_pps.state = "Unusable";
break;
default:
msgClockInfo_pps.state = "Error while retreiving mode";
break;
}
msgClockInfo_pps.name = pps_.substr(2,3);
//msgClockInfo_pps.mode = pps_.substr(0,1); -> switch case
//msgClockInfo_pps.state = pps_.substr(1,1); -> switch case
msgClockInfo_pps.adjusted_offset = t1_pps; // substring to send data from 1st sign
msgClockInfo_pps.measured_offset = t2_pps; // substring to send data from 2nd sign
msgClockInfo_pps.estimated_error = t3_pps; // substring to send data from last sign
msgClockList.list = {msgClockInfo_gps, msgClockInfo_pps};
msgClockList.raw_data = gps_ + pps_;
// std::cout << t1_gps.nsec << " " << t2_gps.nsec << " " << t3_gps.nsec << std::endl;
// std::cout << t1_pps.nsec << " " << t2_pps.nsec << " " << t3_pps.nsec << std::endl;
pubGPSClock.publish(msgClockInfo_gps);
pubPPSClock.publish(msgClockInfo_pps);
pubListClock.publish(msgClockList);
// close file
pclose(fp);
rate.sleep();
}
return 0;
}
\ No newline at end of file
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment