adding node path and time stamp to parameter event message (#584)
modify adding clock for rclcpp_lifestyle
This commit is contained in:
parent
9c25ba9a4a
commit
9d7b50e4f7
6 changed files with 34 additions and 23 deletions
|
@ -471,8 +471,8 @@ private:
|
||||||
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
|
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
|
||||||
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
|
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
|
||||||
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
|
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
|
||||||
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
|
|
||||||
rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
|
rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
|
||||||
|
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
|
||||||
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
|
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
|
||||||
|
|
||||||
bool use_intra_process_comms_;
|
bool use_intra_process_comms_;
|
||||||
|
|
|
@ -51,6 +51,7 @@ public:
|
||||||
const node_interfaces::NodeBaseInterface::SharedPtr node_base,
|
const node_interfaces::NodeBaseInterface::SharedPtr node_base,
|
||||||
const node_interfaces::NodeTopicsInterface::SharedPtr node_topics,
|
const node_interfaces::NodeTopicsInterface::SharedPtr node_topics,
|
||||||
const node_interfaces::NodeServicesInterface::SharedPtr node_services,
|
const node_interfaces::NodeServicesInterface::SharedPtr node_services,
|
||||||
|
const node_interfaces::NodeClockInterface::SharedPtr node_clock,
|
||||||
const std::vector<Parameter> & initial_parameters,
|
const std::vector<Parameter> & initial_parameters,
|
||||||
bool use_intra_process,
|
bool use_intra_process,
|
||||||
bool start_parameter_services);
|
bool start_parameter_services);
|
||||||
|
@ -120,6 +121,10 @@ private:
|
||||||
Publisher<rcl_interfaces::msg::ParameterEvent>::SharedPtr events_publisher_;
|
Publisher<rcl_interfaces::msg::ParameterEvent>::SharedPtr events_publisher_;
|
||||||
|
|
||||||
std::shared_ptr<ParameterService> parameter_service_;
|
std::shared_ptr<ParameterService> parameter_service_;
|
||||||
|
|
||||||
|
std::string combined_name_;
|
||||||
|
|
||||||
|
node_interfaces::NodeClockInterface::SharedPtr node_clock_;
|
||||||
};
|
};
|
||||||
|
|
||||||
} // namespace node_interfaces
|
} // namespace node_interfaces
|
||||||
|
|
|
@ -67,14 +67,6 @@ Node::Node(
|
||||||
node_timers_(new rclcpp::node_interfaces::NodeTimers(node_base_.get())),
|
node_timers_(new rclcpp::node_interfaces::NodeTimers(node_base_.get())),
|
||||||
node_topics_(new rclcpp::node_interfaces::NodeTopics(node_base_.get())),
|
node_topics_(new rclcpp::node_interfaces::NodeTopics(node_base_.get())),
|
||||||
node_services_(new rclcpp::node_interfaces::NodeServices(node_base_.get())),
|
node_services_(new rclcpp::node_interfaces::NodeServices(node_base_.get())),
|
||||||
node_parameters_(new rclcpp::node_interfaces::NodeParameters(
|
|
||||||
node_base_,
|
|
||||||
node_topics_,
|
|
||||||
node_services_,
|
|
||||||
initial_parameters,
|
|
||||||
use_intra_process_comms,
|
|
||||||
start_parameter_services
|
|
||||||
)),
|
|
||||||
node_clock_(new rclcpp::node_interfaces::NodeClock(
|
node_clock_(new rclcpp::node_interfaces::NodeClock(
|
||||||
node_base_,
|
node_base_,
|
||||||
node_topics_,
|
node_topics_,
|
||||||
|
@ -82,6 +74,15 @@ Node::Node(
|
||||||
node_services_,
|
node_services_,
|
||||||
node_logging_
|
node_logging_
|
||||||
)),
|
)),
|
||||||
|
node_parameters_(new rclcpp::node_interfaces::NodeParameters(
|
||||||
|
node_base_,
|
||||||
|
node_topics_,
|
||||||
|
node_services_,
|
||||||
|
node_clock_,
|
||||||
|
initial_parameters,
|
||||||
|
use_intra_process_comms,
|
||||||
|
start_parameter_services
|
||||||
|
)),
|
||||||
node_waitables_(new rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
|
node_waitables_(new rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
|
||||||
use_intra_process_comms_(use_intra_process_comms)
|
use_intra_process_comms_(use_intra_process_comms)
|
||||||
{
|
{
|
||||||
|
|
|
@ -36,9 +36,11 @@ NodeParameters::NodeParameters(
|
||||||
const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
|
const rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
|
||||||
const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics,
|
const rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics,
|
||||||
const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services,
|
const rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services,
|
||||||
|
const rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock,
|
||||||
const std::vector<rclcpp::Parameter> & initial_parameters,
|
const std::vector<rclcpp::Parameter> & initial_parameters,
|
||||||
bool use_intra_process,
|
bool use_intra_process,
|
||||||
bool start_parameter_services)
|
bool start_parameter_services)
|
||||||
|
: node_clock_(node_clock)
|
||||||
{
|
{
|
||||||
using MessageT = rcl_interfaces::msg::ParameterEvent;
|
using MessageT = rcl_interfaces::msg::ParameterEvent;
|
||||||
using PublisherT = rclcpp::Publisher<MessageT>;
|
using PublisherT = rclcpp::Publisher<MessageT>;
|
||||||
|
@ -105,11 +107,11 @@ NodeParameters::NodeParameters(
|
||||||
// Should never happen
|
// Should never happen
|
||||||
throw std::runtime_error("Node name and namespace were not set");
|
throw std::runtime_error("Node name and namespace were not set");
|
||||||
}
|
}
|
||||||
std::string combined_name;
|
|
||||||
if ('/' == node_namespace.at(node_namespace.size() - 1)) {
|
if ('/' == node_namespace.at(node_namespace.size() - 1)) {
|
||||||
combined_name = node_namespace + node_name;
|
combined_name_ = node_namespace + node_name;
|
||||||
} else {
|
} else {
|
||||||
combined_name = node_namespace + '/' + node_name;
|
combined_name_ = node_namespace + '/' + node_name;
|
||||||
}
|
}
|
||||||
|
|
||||||
std::map<std::string, rclcpp::Parameter> parameters;
|
std::map<std::string, rclcpp::Parameter> parameters;
|
||||||
|
@ -131,7 +133,7 @@ NodeParameters::NodeParameters(
|
||||||
|
|
||||||
rclcpp::ParameterMap initial_map = rclcpp::parameter_map_from(yaml_params);
|
rclcpp::ParameterMap initial_map = rclcpp::parameter_map_from(yaml_params);
|
||||||
rcl_yaml_node_struct_fini(yaml_params);
|
rcl_yaml_node_struct_fini(yaml_params);
|
||||||
auto iter = initial_map.find(combined_name);
|
auto iter = initial_map.find(combined_name_);
|
||||||
if (initial_map.end() == iter) {
|
if (initial_map.end() == iter) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
@ -186,6 +188,8 @@ NodeParameters::set_parameters_atomically(
|
||||||
std::map<std::string, rclcpp::Parameter> tmp_map;
|
std::map<std::string, rclcpp::Parameter> tmp_map;
|
||||||
auto parameter_event = std::make_shared<rcl_interfaces::msg::ParameterEvent>();
|
auto parameter_event = std::make_shared<rcl_interfaces::msg::ParameterEvent>();
|
||||||
|
|
||||||
|
parameter_event->node = combined_name_;
|
||||||
|
|
||||||
// TODO(jacquelinekay): handle parameter constraints
|
// TODO(jacquelinekay): handle parameter constraints
|
||||||
rcl_interfaces::msg::SetParametersResult result;
|
rcl_interfaces::msg::SetParametersResult result;
|
||||||
if (parameters_callback_) {
|
if (parameters_callback_) {
|
||||||
|
@ -228,7 +232,7 @@ NodeParameters::set_parameters_atomically(
|
||||||
}
|
}
|
||||||
|
|
||||||
std::swap(tmp_map, parameters_);
|
std::swap(tmp_map, parameters_);
|
||||||
|
parameter_event->stamp = node_clock_->get_clock()->now();
|
||||||
events_publisher_->publish(parameter_event);
|
events_publisher_->publish(parameter_event);
|
||||||
|
|
||||||
return result;
|
return result;
|
||||||
|
|
|
@ -519,8 +519,8 @@ private:
|
||||||
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
|
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers_;
|
||||||
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
|
rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr node_topics_;
|
||||||
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
|
rclcpp::node_interfaces::NodeServicesInterface::SharedPtr node_services_;
|
||||||
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
|
|
||||||
rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
|
rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_;
|
||||||
|
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_parameters_;
|
||||||
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
|
rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_;
|
||||||
|
|
||||||
bool use_intra_process_comms_;
|
bool use_intra_process_comms_;
|
||||||
|
|
|
@ -74,14 +74,6 @@ LifecycleNode::LifecycleNode(
|
||||||
node_timers_(new rclcpp::node_interfaces::NodeTimers(node_base_.get())),
|
node_timers_(new rclcpp::node_interfaces::NodeTimers(node_base_.get())),
|
||||||
node_topics_(new rclcpp::node_interfaces::NodeTopics(node_base_.get())),
|
node_topics_(new rclcpp::node_interfaces::NodeTopics(node_base_.get())),
|
||||||
node_services_(new rclcpp::node_interfaces::NodeServices(node_base_.get())),
|
node_services_(new rclcpp::node_interfaces::NodeServices(node_base_.get())),
|
||||||
node_parameters_(new rclcpp::node_interfaces::NodeParameters(
|
|
||||||
node_base_,
|
|
||||||
node_topics_,
|
|
||||||
node_services_,
|
|
||||||
initial_parameters,
|
|
||||||
use_intra_process_comms,
|
|
||||||
start_parameter_services
|
|
||||||
)),
|
|
||||||
node_clock_(new rclcpp::node_interfaces::NodeClock(
|
node_clock_(new rclcpp::node_interfaces::NodeClock(
|
||||||
node_base_,
|
node_base_,
|
||||||
node_topics_,
|
node_topics_,
|
||||||
|
@ -89,6 +81,15 @@ LifecycleNode::LifecycleNode(
|
||||||
node_services_,
|
node_services_,
|
||||||
node_logging_
|
node_logging_
|
||||||
)),
|
)),
|
||||||
|
node_parameters_(new rclcpp::node_interfaces::NodeParameters(
|
||||||
|
node_base_,
|
||||||
|
node_topics_,
|
||||||
|
node_services_,
|
||||||
|
node_clock_,
|
||||||
|
initial_parameters,
|
||||||
|
use_intra_process_comms,
|
||||||
|
start_parameter_services
|
||||||
|
)),
|
||||||
node_waitables_(new rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
|
node_waitables_(new rclcpp::node_interfaces::NodeWaitables(node_base_.get())),
|
||||||
use_intra_process_comms_(use_intra_process_comms),
|
use_intra_process_comms_(use_intra_process_comms),
|
||||||
impl_(new LifecycleNodeInterfaceImpl(node_base_, node_services_))
|
impl_(new LifecycleNodeInterfaceImpl(node_base_, node_services_))
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue