Skip to content

Commit 5f7c42c

Browse files
committed
added ros time usage tutorial
1 parent e165ad3 commit 5f7c42c

File tree

4 files changed

+132
-0
lines changed

4 files changed

+132
-0
lines changed
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
cmake_minimum_required(VERSION 2.8.3)
2+
project(ros_time_examples)
3+
4+
find_package(catkin REQUIRED COMPONENTS
5+
geometry_msgs
6+
roscpp
7+
rospy
8+
std_msgs
9+
message_generation
10+
)
11+
12+
catkin_package(
13+
CATKIN_DEPENDS
14+
roscpp
15+
rospy
16+
)
17+
18+
include_directories(
19+
${catkin_INCLUDE_DIRS}
20+
)
21+
22+
add_executable(simple_time_example_cpp_node
23+
ros/src/simple_time_example_node.cpp)
24+
25+
target_link_libraries(simple_time_example_cpp_node
26+
${catkin_LIBRARIES}
27+
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
<?xml version="1.0"?>
2+
<package>
3+
<name>ros_time_examples</name>
4+
<version>0.1.0</version>
5+
<description>The ros_time_examples package</description>
6+
7+
<maintainer email="[email protected]">Shehzad Ahmed</maintainer>
8+
9+
<license>GPLv3</license>
10+
11+
<buildtool_depend>catkin</buildtool_depend>
12+
<build_depend>roscpp</build_depend>
13+
<build_depend>rospy</build_depend>
14+
15+
<run_depend>roscpp</run_depend>
16+
<run_depend>rospy</run_depend>
17+
</package>
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,37 @@
1+
#!/usr/bin/env python
2+
"""
3+
This script initilizes simple python node.
4+
"""
5+
#-*- encoding: utf-8 -*-
6+
__author__ = 'shehzad ahmed'
7+
import rospy
8+
from ros_services_examples.srv import *
9+
10+
def initlize_node():
11+
'''
12+
Initilize node and spin which simply keeps python
13+
from exiting until this node is stopped
14+
'''
15+
rospy.init_node('simple_time_example_node', anonymous=False)
16+
rospy.loginfo("simple_time_example_node is now running")
17+
18+
now1 = rospy.Time.now()
19+
rospy.loginfo("Current time (now1): %i %i", now1.secs, now1.nsecs)
20+
21+
now2 = rospy.get_rostime()
22+
rospy.loginfo("Current time (now2): %i %i", now2.secs, now2.nsecs)
23+
24+
rospy.sleep(10.)
25+
26+
d = rospy.Duration(10, 0)
27+
rospy.sleep(d)
28+
29+
r = rospy.Rate(10) # 10hz
30+
while not rospy.is_shutdown():
31+
r.sleep()
32+
33+
34+
rospy.spin()
35+
36+
if __name__ == '__main__':
37+
initlize_node()
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,51 @@
1+
/**
2+
* simple_time_example_node.cpp
3+
*
4+
* Created on: September 10, 2014
5+
* Author: Shehzad Ahmed
6+
**/
7+
#include <ros/ros.h>
8+
9+
void rosTimeExamples()
10+
{
11+
ros::Time now = ros::Time::now();
12+
13+
ROS_INFO_STREAM("Time Now:" << now);
14+
15+
ros::Duration duration(5.0);
16+
17+
ROS_INFO_STREAM("duration:" << duration);
18+
19+
//ROS duration sleep()
20+
ros::Duration(0.5).sleep();
21+
22+
ros::Rate r(10); // 10 hz
23+
while (ros::ok())
24+
{
25+
r.sleep();
26+
}
27+
}
28+
29+
int main(int argc, char *argv[])
30+
{
31+
/*
32+
* Initilization of node
33+
*/
34+
ros::init(argc, argv, "simple_time_example_node");
35+
36+
/*
37+
* Starting node.
38+
*/
39+
ros::NodeHandle nh("~");
40+
41+
/**
42+
* Printing Information message on the console.
43+
**/
44+
ROS_INFO("simple_time_example_node is now running");
45+
46+
rosTimeExamples();
47+
48+
//ros::spin();
49+
50+
return 0;
51+
}

0 commit comments

Comments
 (0)