mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
Started structure for non real time data parsing
This commit is contained in:
@@ -9,8 +9,8 @@
|
|||||||
* ----------------------------------------------------------------------------
|
* ----------------------------------------------------------------------------
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#ifndef ROBOTSTATERT_H_
|
#ifndef ROBOT_STATE_RT_H_
|
||||||
#define ROBOTSTATERT_H_
|
#define ROBOT_STATE_RT_H_
|
||||||
|
|
||||||
#include <inttypes.h>
|
#include <inttypes.h>
|
||||||
#include <vector>
|
#include <vector>
|
||||||
@@ -99,4 +99,4 @@ public:
|
|||||||
void unpack(uint8_t * buf);
|
void unpack(uint8_t * buf);
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif /* ROBOTSTATERT_H_ */
|
#endif /* ROBOT_STATE_RT_H_ */
|
||||||
|
|||||||
@@ -13,6 +13,14 @@
|
|||||||
<arg name="max_payload"/>
|
<arg name="max_payload"/>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- The max_velocity parameter is only used for debugging in the ur_driver. It's not related to actual velocity limits -->
|
||||||
|
<arg name="max_velocity" default="10.0"/> <!-- [rad/s] -->
|
||||||
|
|
||||||
|
<!-- copy the specified IP address to be consistant with ROS-Industrial spec.
|
||||||
|
NOTE: The ip address is actually passed to the driver on the command line -->
|
||||||
|
<param name="/robot_ip_address" type="str" value="$(arg robot_ip)"/>
|
||||||
|
|
||||||
|
|
||||||
<!-- copy the specified IP address to be consistant with ROS-Industrial spec.
|
<!-- copy the specified IP address to be consistant with ROS-Industrial spec.
|
||||||
NOTE: The ip address is actually passed to the driver on the command line -->
|
NOTE: The ip address is actually passed to the driver on the command line -->
|
||||||
<param name="/robot_ip_address" type="str" value="$(arg robot_ip)"/>
|
<param name="/robot_ip_address" type="str" value="$(arg robot_ip)"/>
|
||||||
|
|||||||
Reference in New Issue
Block a user