Go to the documentation of this file.
69 int main(
int argc,
char** argv)
71 ros::init(argc, argv,
"psen_scan_v2_node");
79 getOptionalParamFromServer<double>(
82 getOptionalParamFromServer<double>(
105 if (scanner_configuration.fragmentedScansEnabled())
107 ROS_INFO(
"Using fragmented scans.");
114 scanner_configuration);
118 ros_scanner_node.
run();
120 catch (std::exception&
e)
123 std::cerr <<
"\x1B[91m" <<
e.what() <<
"\033[0m\n";
static constexpr unsigned short DATA_PORT_OF_HOST_DEVICE
ScannerConfigurationBuilder & hostIP(const std::string &host_ip)
const std::string PARAM_NR_SUBSCRIBERS
REGISTER_ROSCONSOLE_BRIDGE
ScannerConfigurationBuilder & nrSubscribers(const uint8_t &nr_subscribers)
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
void terminate()
Terminates the fetching and publishing of scanner data.
ROS Node that continuously publishes scan data of a single PSENscan laser scanner.
ScannerConfigurationBuilder & enableDiagnostics(const bool &enable)
static constexpr double DEFAULT_SCAN_ANGLE_RESOLUTION(data_conversion_layer::degreeToRadian(0.1))
const std::string PARAM_SCANNER_IP
static TenthOfDegree fromRad(const double &angle_in_rad)
ROSCPP_DECL void shutdown()
const std::string PARAM_INTENSITIES
void delayed_shutdown_sig_handler(int sig)
static constexpr double DEFAULT_ANGLE_START(-data_conversion_layer::degreeToRadian(137.4))
Start angle of measurement.
ScannerConfigurationBuilder & scanRange(const ScanRange &scan_range)
static constexpr unsigned short CONTROL_PORT_OF_HOST_DEVICE
const std::string PARAM_HOST_CONTROL_PORT
ScannerConfigurationBuilder & scanResolution(const util::TenthOfDegree &scan_resolution)
ScannerConfiguration build() const
static constexpr bool INTENSITIES
const std::string PARAM_TF_PREFIX
Root namespace for the ROS part.
static constexpr unsigned short CONTROL_PORT_OF_SCANNER_DEVICE
static const std::string DEFAULT_PUBLISH_TOPIC
Topic on which the LaserScan data are published.
ScannerConfigurationBuilder & scannerDataPort(const int &scanner_data_port)
static const std::string DEFAULT_HOST_IP_STRING
int main(int argc, char **argv)
ScannerConfigurationBuilder & enableIntensities(const bool &enable)
ScannerConfigurationBuilder & scannerControlPort(const int &scanner_control_port)
const std::string PARAM_HOST_IP
static constexpr double DEFAULT_ANGLE_END(data_conversion_layer::degreeToRadian(137.4))
End angle of measurement.
void run()
Continuously fetches data from the scanner and publishes the data into the ROS network.
const std::string PARAM_FRAGMENTED_SCANS
static constexpr double DEFAULT_X_AXIS_ROTATION
The 2D scan will be rotated around the z-axis.
Helper class to simplify/improve the construction of the psen_scan_v2_standalone::ScannerConfiguratio...
static const std::string DEFAULT_TF_PREFIX
const std::string PARAM_RESOLUTION
const std::string PARAM_ANGLE_END
Root namespace in which the software components to communicate with the scanner (firmware-version: 2)...
std::function< void()> NODE_TERMINATE_CALLBACK
const std::string PARAM_HOST_DATA_PORT
const std::string PARAM_X_AXIS_ROTATION
Higher level data type storing the range in which the scanner takes measurements.
static constexpr unsigned short NR_SUBSCRIBERS
static constexpr unsigned short DATA_PORT_OF_SCANNER_DEVICE
ScannerConfigurationBuilder & enableFragmentedScans(const bool &enable)
ScannerConfigurationBuilder & hostDataPort(const int &host_data_port)
static constexpr bool FRAGMENTED_SCANS
Contains the events needed to define and implement the scanner protocol.
const std::string PARAM_ANGLE_START
ScannerConfigurationBuilder & hostControlPort(const int &host_control_port)
Higher level data type storing the configuration details of the scanner like scanner IP,...
psen_scan_v2
Author(s): Pilz GmbH + Co. KG
autogenerated on Sat Jun 22 2024 02:46:11