Program Listing for File speed_scaling_state_broadcaster.hpp
↰ Return to documentation for file (include/ur_controllers/speed_scaling_state_broadcaster.hpp
)
// Copyright 2019, FZI Forschungszentrum Informatik
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above copyright
// notice, this list of conditions and the following disclaimer in the
// documentation and/or other materials provided with the distribution.
//
// * Neither the name of the {copyright_holder} nor the names of its
// contributors may be used to endorse or promote products derived from
// this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//----------------------------------------------------------------------
//----------------------------------------------------------------------
#ifndef UR_CONTROLLERS__SPEED_SCALING_STATE_BROADCASTER_HPP_
#define UR_CONTROLLERS__SPEED_SCALING_STATE_BROADCASTER_HPP_
#include <memory>
#include <string>
#include <vector>
#include "controller_interface/controller_interface.hpp"
#include "rclcpp_lifecycle/lifecycle_publisher.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp/duration.hpp"
#include "std_msgs/msg/float64.hpp"
#include "speed_scaling_state_broadcaster_parameters.hpp"
namespace ur_controllers
{
class SpeedScalingStateBroadcaster : public controller_interface::ControllerInterface
{
public:
SpeedScalingStateBroadcaster();
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
controller_interface::return_type update(const rclcpp::Time& time, const rclcpp::Duration& period) override;
controller_interface::CallbackReturn on_configure(const rclcpp_lifecycle::State& previous_state) override;
controller_interface::CallbackReturn on_activate(const rclcpp_lifecycle::State& previous_state) override;
controller_interface::CallbackReturn on_deactivate(const rclcpp_lifecycle::State& previous_state) override;
controller_interface::CallbackReturn on_init() override;
protected:
std::vector<std::string> sensor_names_;
double publish_rate_;
std::shared_ptr<rclcpp::Publisher<std_msgs::msg::Float64>> speed_scaling_state_publisher_;
std_msgs::msg::Float64 speed_scaling_state_msg_;
// Parameters from ROS for SpeedScalingStateBroadcaster
std::shared_ptr<speed_scaling_state_broadcaster::ParamListener> param_listener_;
speed_scaling_state_broadcaster::Params params_;
};
} // namespace ur_controllers
#endif // UR_CONTROLLERS__SPEED_SCALING_STATE_BROADCASTER_HPP_