zlp_projector_ros module

ROS node class which provides a collection of services that allows to operate and control the ZLP1 laser projector and simplify the task of developing further advanced features.

class z_laser_zlp1.zlp_projector_ros.ZLPProjectorROS(projector_IP, server_IP, connection_port, license_path)[source]

Bases: object

This class initilizes the services and implements the functionalities of the node.

Parameters:
  • projector_IP (str) – IP number of projector device
  • server_IP (str) – IP number of service running at projector device
  • connection_port (int) – connection port number
  • license_path (str) – path of license file
lic_path

folder path where Z-Laser license file is located

Type:str
projector

ZLPProjectorManager object from projector_manager library

Type:object
run_viz

true if visualizer is running, false otherwise

Type:bool
STD_WAIT_TIME

predefined number of projection seconds in reference system definition

Type:int
__init__(projector_IP, server_IP, connection_port, license_path)[source]

Initialize the ZLPProjectorROS object.

open_services()[source]

Open ROS services that allow projector device control.

set_viz_run(run)[source]

Set status of run_viz attribute and define ROS publisher if required.

Parameters:run (bool) – true if visulizer is running, false otherwise
connection_cb(req)[source]

Callback of ROS service to connect to ZLP-Server, transfer license and activate projector.

Parameters:req (object) – trigger request ROS service object
Returns:the first value in the returned tuple is a bool success value and the second value in the tuple is an information message string
Return type:tuple[bool, str]
disconnection_cb(req)[source]

Callback of ROS service to deactivate projector and disconnect from ZLP-Server.

Parameters:req (object) – trigger request ROS service object
Returns:the first value in the returned tuple is a bool success value and the second value in the tuple is an information message string
Return type:tuple[bool, str]
projection_start_cb(req)[source]

Callback of ROS service to start projection of elements related to the active reference system on the surface. (see set_coord_sys_cb())

Parameters:req (object) – trigger request ROS service object
Returns:the first value in the returned tuple is a bool success value and the second value in the tuple is an information message string
Return type:tuple[bool, str]
projection_stop_cb(req)[source]

Callback of ROS service to stop projection of all elements.

Parameters:req (object) – trigger request ROS service object
Returns:the first value in the returned tuple is a bool success value and the second value in the tuple is an information message string
Return type:tuple[bool, str]
manual_define_coord_sys_cb(req)[source]

Callback of ROS service to define a new reference system, stating the points coordinates manually by the user.

Parameters:req (object) – object with the necessary parameters to define a new coordinate system
Returns:the first value in the returned tuple is a list of the user reference points T0, T1, T2, T3, the second is a bool success value and the third s an information message string
Return type:tuple[list, bool, str]
auto_search_target_cb(req)[source]

Callback of ROS service to define a new reference system by scanning the targets automatically with the projector.

Parameters:req (object) – object with the necessary parameters to define a new coordinate system by scanning targets
Returns:the first value in the returned tuple is a list of the user reference points T0, T1, T2, T3, the second is a bool success value and the third s an information message string
Return type:tuple[list, bool, str]
get_coord_sys_list_cb(req)[source]

Callback of ROS service to get the list of defined reference systems.

Parameters:req (object) – ROS service CoordinateSystemList request object is empty
Returns:the first value in the returned tuple is a bool success value, the second is an information message string, the third is a list of the defined reference systems and the last is the name of the active reference system
Return type:tuple[bool, str, list, str]
set_coord_sys_cb(req)[source]

Callback of ROS service to set the indicated reference system as ‘active reference system’. It means that services as projection_start or show_active_coordinate_system, etc. automatically use this active reference system to perform their task. The rest of coordinate systems are defined and stored in the projector, staying on background until any is set as active again.

Parameters:req (object) – object with the necessary parameters to identify a coordinate system
Returns:the first value in the returned tuple is a bool success value and the second value in the tuple is an information message string
Return type:tuple[bool, str]
show_coord_sys_cb(req)[source]

Callback of ROS service to project reference points, origin axes and frame of the active reference system.

Parameters:req (object) – object with the necessary parameters to identify a reference system
Returns:the first value in the returned tuple is a bool success value and the second value in the tuple is an information message string
Return type:tuple[bool, str]
remove_coord_sys_cb(req)[source]

Callback of ROS service to remove a reference system.

Parameters:req (object) – object with the necessary parameters to identify a reference system
Returns:the first value in the returned tuple is a bool success value and the second value in the tuple is an information message string
Return type:tuple[bool, str]
add_fig_cb(msg)[source]

Callback of ROS topic to define a new projection element.

Parameters:msg (object) – object with the necessary parameters to define a new projection element
hide_proj_elem_cb(req)[source]

Callback of ROS service to hide specific projection element from active reference system.

Parameters:req (object) – object with the necessary parameters to identify a projection element
Returns:the first value in the returned tuple is a bool success value and the second value in the tuple is an information message string
Return type:tuple[bool, str]
unhide_proj_elem_cb(req)[source]

Callback of ROS service to unhide specific projection element from active reference system.

Parameters:req (object) – object with the necessary parameters to identify a projection element
Returns:the first value in the returned tuple is a bool success value and the second value in the tuple is an information message string
Return type:tuple[bool, str]
remove_proj_elem_cb(req)[source]

Callback of ROS service to remove specific figure from active reference system.

Parameters:req (object) – object with the necessary parameters to identify a projection element
Returns:the first value in the returned tuple is a bool success value and the second value in the tuple is an information message string
Return type:tuple[bool, str]
keyboard_monitor_proj_elem_cb(req)[source]

Callback of ROS service to apply different transformations (translation, rotation, scalation) to a specific projection element on real time by the use of keyboard.

Parameters:req (object) – object with the necessary parameters to identify a projection element
Returns:the first value in the returned tuple is a bool success value and the second value in the tuple is an information message string
Return type:tuple[bool, str]
add_pointer_cb(msg)[source]

Callback of ROS topic to define a new pointer.

Parameters:msg (object) – object with the necessary parameters to define a new pointer
pointer_cb_example(name, reflection)[source]

Callback example for reflection state change, events handler. It is used for running code when pointer is reflected.

Parameters:
  • name (str) – name of the pointer that changed state
  • reflection (bool) – true if a reflection was detected; False otherwise
scan_pointer_cb(req)[source]

Callback of ROS service to start pointers scanning.

Parameters:req (object) – trigger request ROS service object
Returns:the first value in the returned tuple is a bool success value and the second value in the tuple is an information message string
Return type:tuple[bool, str]
set_rosparam_coordinate_system(cs_params)[source]

Set rosparams from given reference system.

Parameters:cs_params (object) – object with the parameters of a reference system
read_rosparam_coordinate_system()[source]

Get parameters of the active reference system from rosparams.

Returns:object with the parameters of the active reference system
Return type:cs_params (object)
setup_projector()[source]

Setup projector at initialization (connect to ZLP-Service, transfer license file and activate projector).

Returns:success value. True if success, False otherwise.
Return type:bool
initialize_coordinate_system()[source]

Initial projector setup with the factory or an user predefined reference system from configuration files.

shutdown_handler()[source]

Handler to close connection when node exits.

Returns:the first value in the returned tuple is a bool success value and the second value in the tuple is an information message string
Return type:tuple[bool, str]