ros::duration-sleep do not return with minus value
k-okada opened this issue · 0 comments
k-okada commented
#459 added ros::duration-sleep()
but the behavior with minus values not tested.
On python, it returns immediately
>>> a = rospy.Time.now() ; rospy.sleep(rospy.Duration(1)); print((rospy.Time.now()-a).to_sec())
1.001641989
>>> a = rospy.Time.now() ; rospy.sleep(rospy.Duration(-1)); print((rospy.Time.now()-a).to_sec())
0.00012803
and on C++, it never returns (or will return after INT_MAX-1
[sec])
k-okada@p51s:/tmp$ cat hoge.c
#include <ros/ros.h>
int main(int argc, char **argv) {
ros::init(argc, argv, "test");
ros::NodeHandle();
ros::Time a = ros::Time::now();
ros::Duration(1).sleep();
std::cerr << (ros::Time::now() - a).toSec() << std::endl;
a = ros::Time::now();
ros::Duration(-1).sleep();
std::cerr << (ros::Time::now() - a).toSec() << std::endl;
}
k-okada@p51s:/tmp$ g++ -o hoge hoge.c -I/opt/ros/kinetic/include -L/opt/ros/kinetic/lib -lroscpp -lrostime && ./hoge
1.00009
^C12.8579
and roseus behaves similar to roscpp, I think it should be returned immediately.
(ros::roseus "test")
(setq tm0 (ros::time-now))
(send (instance ros::duration :init 1.5) :sleep)
(setq tm1 (ros::time-now))
(print (send (ros::time- tm1 tm0) :to-sec))
(setq tm0 (ros::time-now))
(send (instance ros::duration :init -1.5) :sleep)
(setq tm1 (ros::time-now))
(print (send (ros::time- tm1 tm0) :to-sec))
``