blob: a52dd793c664bb0e9794f25452aa9ea310a3808b [file] [log] [blame]
// --------------------------------------------------------
// Copyright (c)
//
// contributions by author
// author@somewhere.net
// maintained by maintainer
// maintainer@somewhere.net
// --------------------------------------------------------
// Code generated by Papyrus C++
// --------------------------------------------------------
#define dummy_joint_statesCompdef_Dummy_joint_states_impl_BODY
/************************************************************
Dummy_joint_states_impl class body
************************************************************/
// include associated header file
#include "dummy_joint_statesCompdef/Dummy_joint_states_impl.h"
// Derived includes directives
#include "rclcpp/rclcpp.hpp"
#include "rclcpp/clock.hpp"
#include "rclcpp/time_source.hpp"
namespace dummy_joint_statesCompdef {
// static attributes (if any)
/**
*
* @param options
*/
Dummy_joint_states_impl::Dummy_joint_states_impl(
rclcpp::NodeOptions /*in*/options) :
Dummy_joint_states(options) {
}
/**
*
*/
void Dummy_joint_states_impl::activateFct() {
msg.name.push_back("single_rrbot_joint1");
msg.name.push_back("single_rrbot_joint2");
msg.position.push_back(0.0);
msg.position.push_back(0.0);
}
/**
*
*/
void Dummy_joint_states_impl::periodicFct() {
counter += step_;
RCLCPP_INFO(get_logger(), "counter %f", counter);
auto joint_value = std::sin(counter);
for (size_t i = 0; i < msg.name.size(); ++i) {
msg.position[i] = joint_value;
}
msg.header.stamp = get_clock()->now();
joint_states_pub_->publish(msg);
}
} // of namespace dummy_joint_statesCompdef
/************************************************************
End of Dummy_joint_states_impl class body
************************************************************/