Class SickS300

Inheritance Relationships

Base Type

  • public rclcpp_lifecycle::LifecycleNode

Class Documentation

class SickS300 : public rclcpp_lifecycle::LifecycleNode

ROS2 driver for the SICK S300 Professional laser scanner.

Public Functions

explicit SickS300(const rclcpp::NodeOptions &options = rclcpp::NodeOptions())

Construct a new Sick S300 object.

Parameters:

options – Node options

~SickS300()

Destroy the Sick S300 object.

CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override

Configure the node.

Parameters:

state – State of the node

Returns:

CallbackReturn

CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override

Activate the node.

Parameters:

state – State of the node

Returns:

CallbackReturn

CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override

Deactivate the node.

Parameters:

state – State of the node

Returns:

CallbackReturn

CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override

Cleanup the node.

Parameters:

state – State of the node

Returns:

CallbackReturn

CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override

Shutdown the node.

Parameters:

state – State of the node

Returns:

CallbackReturn

Protected Functions

template<typename NodeT>
inline void declare_parameter_if_not_declared(NodeT node, const std::string &param_name, const rclcpp::ParameterValue &default_value, const rcl_interfaces::msg::ParameterDescriptor &parameter_descriptor = rcl_interfaces::msg::ParameterDescriptor())

Declares static ROS2 parameter and sets it to a given value if it was not already declared.

Parameters:
  • node – A node in which given parameter to be declared

  • param_name – The name of parameter

  • default_value – Parameter value to initialize with

  • parameter_descriptor – Parameter descriptor (optional)

bool open()

Open the scanner.

Returns:

true if the scanner is opened

bool receiveScan()

Receive the scan.

Returns:

true if the scan is received

void publishStandby(bool in_standby)

Publish the standby status.

Parameters:

in_standby – Standby status

void publishLaserScan(std::vector<double> vdDistM, std::vector<double> vdAngRAD, std::vector<double> vdIntensAU, unsigned int iSickTimeStamp, unsigned int iSickNow)

Publish the laser scan.

Parameters:
  • vdDistM – Vector of distances in meters

  • vdAngRAD – Vector of angles in radians

  • vdIntensAU – Vector of intensities in arbitrary units

  • iSickTimeStamp – Timestamp of the scan

  • iSickNow – Current timestamp

void publishError(std::string error)

Publish an error message.

Parameters:

error – Error message

void publishWarn(std::string warn)

Publish a warning message.

Parameters:

warn – Warning message

Protected Attributes

rclcpp_lifecycle::LifecyclePublisher<sensor_msgs::msg::LaserScan>::SharedPtr laser_scan_pub_
rclcpp_lifecycle::LifecyclePublisher<std_msgs::msg::Bool>::SharedPtr in_standby_pub_
rclcpp_lifecycle::LifecyclePublisher<diagnostic_msgs::msg::DiagnosticArray>::SharedPtr diag_pub_
rclcpp::TimerBase::SharedPtr timer_
std::string frame_id_
std::string scan_topic_
std::string port_
int baud_
int scan_id_
bool inverted_
bool debug_
bool synced_time_ready_
unsigned int synced_sick_stamp_
double scan_duration_
double scan_cycle_time_
double scan_delay_
double communication_timeout_
std_msgs::msg::Bool in_standby_
rclcpp::Time synced_ros_time_
ScannerSickS300 scanner_