Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use RViz node clock in tools #519

Merged
merged 1 commit into from
Mar 17, 2020
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,7 @@ private Q_SLOTS:

private:
rclcpp::Publisher<geometry_msgs::msg::PoseStamped>::SharedPtr publisher_;
rclcpp::Clock::SharedPtr clock_;

rviz_common::properties::StringProperty * topic_property_;
rviz_common::properties::QosProfileProperty * qos_profile_property_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,7 @@ public Q_SLOTS:
QCursor std_cursor_;
QCursor hit_cursor_;
rclcpp::Publisher<geometry_msgs::msg::PointStamped>::SharedPtr publisher_;
rclcpp::Clock::SharedPtr clock_;

rviz_common::properties::StringProperty * topic_property_;
rviz_common::properties::BoolProperty * auto_deactivate_property_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,6 +73,7 @@ private Q_SLOTS:

private:
rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr publisher_;
rclcpp::Clock::SharedPtr clock_;

rviz_common::properties::StringProperty * topic_property_;
rviz_common::properties::QosProfileProperty * qos_profile_property_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -71,18 +71,21 @@ void GoalTool::onInitialize()

void GoalTool::updateTopic()
{
rclcpp::Node::SharedPtr raw_node =
context_->getRosNodeAbstraction().lock()->get_raw_node();
// TODO(anhosi, wjwwood): replace with abstraction for publishers once available
publisher_ = context_->getRosNodeAbstraction().lock()->get_raw_node()->
publisher_ = raw_node->
template create_publisher<geometry_msgs::msg::PoseStamped>(
topic_property_->getStdString(), qos_profile_);
clock_ = raw_node->get_clock();
}

void GoalTool::onPoseSet(double x, double y, double theta)
{
std::string fixed_frame = context_->getFixedFrame().toStdString();

geometry_msgs::msg::PoseStamped goal;
goal.header.stamp = rclcpp::Clock().now();
goal.header.stamp = clock_->now();
goal.header.frame_id = fixed_frame;

goal.pose.position.x = x;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -86,10 +86,13 @@ void PointTool::deactivate() {}

void PointTool::updateTopic()
{
rclcpp::Node::SharedPtr raw_node =
context_->getRosNodeAbstraction().lock()->get_raw_node();
// TODO(anhosi, wjwwood): replace with abstraction for publishers once available
publisher_ = context_->getRosNodeAbstraction().lock()->get_raw_node()->
publisher_ = raw_node->
template create_publisher<geometry_msgs::msg::PointStamped>(
topic_property_->getStdString(), qos_profile_);
clock_ = raw_node->get_clock();
}

void PointTool::updateAutoDeactivate() {}
Expand Down Expand Up @@ -134,7 +137,7 @@ void PointTool::publishPosition(const Ogre::Vector3 & position) const
geometry_msgs::msg::PointStamped point_stamped;
point_stamped.point = point;
point_stamped.header.frame_id = context_->getFixedFrame().toStdString();
point_stamped.header.stamp = rclcpp::Clock().now();
point_stamped.header.stamp = clock_->now();
publisher_->publish(point_stamped);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -73,9 +73,12 @@ void InitialPoseTool::onInitialize()
void InitialPoseTool::updateTopic()
{
// TODO(anhosi, wjwwood): replace with abstraction for publishers once available
publisher_ = context_->getRosNodeAbstraction().lock()->get_raw_node()->
rclcpp::Node::SharedPtr raw_node =
context_->getRosNodeAbstraction().lock()->get_raw_node();
publisher_ = raw_node->
template create_publisher<geometry_msgs::msg::PoseWithCovarianceStamped>(
topic_property_->getStdString(), qos_profile_);
clock_ = raw_node->get_clock();
}

void InitialPoseTool::onPoseSet(double x, double y, double theta)
Expand All @@ -84,7 +87,7 @@ void InitialPoseTool::onPoseSet(double x, double y, double theta)

geometry_msgs::msg::PoseWithCovarianceStamped pose;
pose.header.frame_id = fixed_frame;
pose.header.stamp = rclcpp::Clock().now();
pose.header.stamp = clock_->now();

pose.pose.pose.position.x = x;
pose.pose.pose.position.y = y;
Expand Down