mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 01:50:46 +02:00
doxygen documentation for hardware interface
This commit is contained in:
@@ -59,25 +59,91 @@ enum class PausingState
|
|||||||
RAMPUP
|
RAMPUP
|
||||||
};
|
};
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief The HardwareInterface class handles the interface between the ROS system and the main
|
||||||
|
* driver. It contains the read and write methods of the main control loop and registers various ROS
|
||||||
|
* topics and services.
|
||||||
|
*/
|
||||||
class HardwareInterface : public hardware_interface::RobotHW
|
class HardwareInterface : public hardware_interface::RobotHW
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
/*!
|
||||||
|
* \brief Creates a new HardwareInterface object.
|
||||||
|
*/
|
||||||
HardwareInterface();
|
HardwareInterface();
|
||||||
virtual ~HardwareInterface() = default;
|
virtual ~HardwareInterface() = default;
|
||||||
|
/*!
|
||||||
|
* \brief Handles the setup functionality for the ROS interface. This includes parsing ROS
|
||||||
|
* parameters, creating interfaces, starting the main driver and advertising ROS services.
|
||||||
|
*
|
||||||
|
* \param root_nh Root level ROS node handle
|
||||||
|
* \param robot_hw_nh ROS node handle for the robot namespace
|
||||||
|
*
|
||||||
|
* \returns True, if the setup was performed successfully
|
||||||
|
*/
|
||||||
virtual bool init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh) override;
|
virtual bool init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw_nh) override;
|
||||||
|
/*!
|
||||||
|
* \brief Read method of the control loop. Reads a RTDE package from the robot and handles and
|
||||||
|
* publishes the information as needed.
|
||||||
|
*
|
||||||
|
* \param time Current time
|
||||||
|
* \param period Duration of current control loop iteration
|
||||||
|
*/
|
||||||
virtual void read(const ros::Time& time, const ros::Duration& period) override;
|
virtual void read(const ros::Time& time, const ros::Duration& period) override;
|
||||||
|
/*!
|
||||||
|
* \brief Write method of the control loop. Writes target joint positions to the robot to be read
|
||||||
|
* by its URCaps program.
|
||||||
|
*
|
||||||
|
* \param time Current time
|
||||||
|
* \param period Duration of current control loop iteration
|
||||||
|
*/
|
||||||
virtual void write(const ros::Time& time, const ros::Duration& period) override;
|
virtual void write(const ros::Time& time, const ros::Duration& period) override;
|
||||||
|
/*!
|
||||||
|
* \brief Preparation to start and stop loaded controllers.
|
||||||
|
*
|
||||||
|
* \param start_list List of controllers to start
|
||||||
|
* \param stop_list List of controllers to stop
|
||||||
|
*
|
||||||
|
* \returns True, if the controllers can be switched
|
||||||
|
*/
|
||||||
virtual bool prepareSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
|
virtual bool prepareSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
|
||||||
const std::list<hardware_interface::ControllerInfo>& stop_list) override;
|
const std::list<hardware_interface::ControllerInfo>& stop_list) override;
|
||||||
|
/*!
|
||||||
|
* \brief Starts and stops controllers.
|
||||||
|
*
|
||||||
|
* \param start_list List of controllers to start
|
||||||
|
* \param stop_list List of controllers to stop
|
||||||
|
*/
|
||||||
virtual void doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
|
virtual void doSwitch(const std::list<hardware_interface::ControllerInfo>& start_list,
|
||||||
const std::list<hardware_interface::ControllerInfo>& stop_list) override;
|
const std::list<hardware_interface::ControllerInfo>& stop_list) override;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Getter for the current control frequency
|
||||||
|
*
|
||||||
|
* \returns The used control frequency
|
||||||
|
*/
|
||||||
uint32_t getControlFrequency() const;
|
uint32_t getControlFrequency() const;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Checks if the URCaps program is running on the robot.
|
||||||
|
*
|
||||||
|
* \returns True, if the program is currently running, false otherwise.
|
||||||
|
*/
|
||||||
bool isRobotProgramRunning() const;
|
bool isRobotProgramRunning() const;
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Callback to handle a change in the current state of the URCaps program running on the
|
||||||
|
* robot.
|
||||||
|
*
|
||||||
|
* \param program_running The new state of the program
|
||||||
|
*/
|
||||||
void handleRobotProgramState(bool program_running);
|
void handleRobotProgramState(bool program_running);
|
||||||
|
|
||||||
|
/*!
|
||||||
|
* \brief Checks if a reset of the ROS controllers is necessary.
|
||||||
|
*
|
||||||
|
* \returns Necessity of ROS controller reset
|
||||||
|
*/
|
||||||
bool shouldResetControllers();
|
bool shouldResetControllers();
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|||||||
Reference in New Issue
Block a user