18 #ifndef MODE_TARGET_HELPER_HPP
19 #define MODE_TARGET_HELPER_HPP
22 #include <boost/numeric/conversion/cast.hpp>
39 std::atomic<bool> has_target_;
50 RCLCPP_DEBUG(rclcpp::get_logger(
"canopen_402_target"),
"Target command is not a number");
54 using boost::numeric_cast;
55 using boost::numeric::negative_overflow;
56 using boost::numeric::positive_overflow;
60 target_ = numeric_cast<T>(val);
62 catch (negative_overflow &)
64 std::cout <<
"canopen_402 Command " << val
65 <<
" does not fit into target, clamping to min limit" << std::endl;
66 target_ = std::numeric_limits<T>::min();
68 catch (positive_overflow &)
70 std::cout <<
"canopen_402 Command " << val
71 <<
" does not fit into target, clamping to max limit" << std::endl;
72 target_ = std::numeric_limits<T>::max();
76 std::cout <<
"canopen_402 Was not able to cast command " << val << std::endl;
Definition: mode_target_helper.hpp:37
virtual bool setTarget(const double &val)
Definition: mode_target_helper.hpp:45
virtual bool start()
Definition: mode_target_helper.hpp:83
bool hasTarget()
Definition: mode_target_helper.hpp:43
T getTarget()
Definition: mode_target_helper.hpp:44
ModeTargetHelper(uint16_t mode)
Definition: mode_target_helper.hpp:42
Definition: configuration_manager.hpp:28