Skip to content

Commit

Permalink
fix rviz_plugin_render_tools topic and null check
Browse files Browse the repository at this point in the history
  • Loading branch information
ddengster committed May 26, 2020
1 parent c7ce58f commit 5421554
Showing 1 changed file with 4 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ TrajectoryVisualization::TrajectoryVisualization(rviz_common::properties::Proper
, trajectory_slider_dock_panel_(nullptr)
{
trajectory_topic_property_ = new rviz_common::properties::RosTopicProperty(
"Trajectory Topic", "/move_group/display_planned_path",
"Trajectory Topic", "/display_planned_path",
rosidl_generator_traits::data_type<moveit_msgs::msg::DisplayTrajectory>(),
"The topic on which the moveit_msgs::msg::DisplayTrajectory messages are received", widget,
SLOT(changedTrajectoryTopic()), this);
Expand Down Expand Up @@ -190,8 +190,10 @@ void TrajectoryVisualization::onRobotModelLoaded(const robot_model::RobotModelCo
enabledRobotColor(); // force-refresh to account for saved display configuration
// perform post-poned subscription to trajectory topic
// Check if topic name is empty
if (trajectory_topic_sub_->get_topic_name())
if (trajectory_topic_sub_ && trajectory_topic_sub_->get_topic_name())
{
changedTrajectoryTopic();
}
}

void TrajectoryVisualization::reset()
Expand Down

0 comments on commit 5421554

Please sign in to comment.