Functions
ROS Namespace Reference

Functions

ROS::NodePtr createNode (const std::string &node_name="sick_scan")
 
void deleteNode (ROS::NodePtr &node)
 
ROS::Duration durationFromSec (double seconds)
 
ROS::Time now (void)
 
double seconds (ROS::Duration duration)
 
double secondsSinceStart (const ROS::Time &time)
 
void sleep (double seconds)
 
void splitTime (ROS::Duration time, uint32_t &seconds, uint32_t &nanoseconds)
 
void splitTime (ROS::Time time, uint32_t &seconds, uint32_t &nanoseconds)
 
ROS::Time timeFromHeader (const std_msgs::Header *msg_header)
 
ROS::Time timeFromSec (double seconds)
 
uint64_t timestampMilliseconds (const ROS::Time &time)
 

Function Documentation

ROS::NodePtr ROS::createNode ( const std::string &  node_name = "sick_scan")

Creates a new ros node, shortcut for new ros::NodeHandle() on ROS1 resp. rclcpp::Node::make_shared(node_name) on ROS2

Definition at line 65 of file ros_wrapper.cpp.

void ROS::deleteNode ( ROS::NodePtr &  node)

Deletes a ros node

ROS1-/ROS2-compatible shortcut for ros::spin(); Deletes a ros node

Definition at line 98 of file ros_wrapper.cpp.

ROS::Duration ROS::durationFromSec ( double  seconds)

Returns a duration (type ros::Duration on ROS1 resp. rclcpp::Duration on ROS2) from a given amount of seconds. Note: ros::Duration(1) initializes 1 second, while rclcpp::Duration(1) initializes 1 nanosecond. Do not use the Duration constructor with one parameter! Always use ROS::durationFromSec(seconds) or ROS::Duration(int32_t seconds, uint32_t nanoseconds).

Definition at line 172 of file ros_wrapper.cpp.

ROS::Time ROS::now ( void  )

Shortcut to return ros::Time::now() on ROS1 resp. rclcpp::Clock::now() on ROS2

Shortcut to ros::Time::now() on ROS1 resp. rclcpp::Clock::now() on ROS2

Definition at line 116 of file ros_wrapper.cpp.

double ROS::seconds ( ROS::Duration  duration)

Shortcut to return ros::Duration::toSec() on ROS1 resp. rclcpp::Duration::seconds() on ROS2

Definition at line 180 of file ros_wrapper.cpp.

double ROS::secondsSinceStart ( const ROS::Time &  time)

Shortcut to return the time in seconds since program start (first node started)

Definition at line 192 of file ros_wrapper.cpp.

void ROS::sleep ( double  seconds)

Shortcut to replace ros::Duration(seconds).sleep() by std::thread

Definition at line 110 of file ros_wrapper.cpp.

void ROS::splitTime ( ROS::Duration  time,
uint32_t &  seconds,
uint32_t &  nanoseconds 
)

Splits a ROS::Duration into seconds and nanoseconds part

Definition at line 128 of file ros_wrapper.cpp.

void ROS::splitTime ( ROS::Time  time,
uint32_t &  seconds,
uint32_t &  nanoseconds 
)

Splits a ROS::Time into seconds and nanoseconds part

Definition at line 140 of file ros_wrapper.cpp.

ROS::Time ROS::timeFromHeader ( const std_msgs::Header msg_header)

Shortcut to return ros::Time(msg_header->stamp.sec,msg_header->stamp.nsec) on ROS1 resp. rclcpp::Time(msg_header->stamp.sec,msg_header->stamp.nanosec) on ROS2

Definition at line 152 of file ros_wrapper.cpp.

ROS::Time ROS::timeFromSec ( double  seconds)

Returns a time (type ros::Time on ROS1 resp. rclcpp::Time on ROS2) from a given amount of seconds. Note: ros::Time(1) initializes 1 second, while rclcpp::Time(1) initializes 1 nanosecond. Do not use the Time constructor with one parameter! Always use ROS::timeFromSec(seconds) or ROS::Time(int32_t seconds, uint32_t nanoseconds).

Definition at line 161 of file ros_wrapper.cpp.

uint64_t ROS::timestampMilliseconds ( const ROS::Time &  time)

Shortcut to return the timestamp in milliseconds from ROS1 resp. ROS2 time

Definition at line 199 of file ros_wrapper.cpp.



sick_scan
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Wed May 5 2021 03:05:49