47
47
48
48
#include " car_pose.hpp"
49
49
50
- #include < unique_identifier_msgs/msg/uuid .hpp>
50
+ #include " util .hpp"
51
51
52
- #include < tf2_geometry_msgs/tf2_geometry_msgs.h>
53
- #include < tf2_ros/transform_listener.h>
52
+ #include < rviz_common/display_context.hpp>
54
53
55
54
#include < algorithm>
56
55
#include < random>
@@ -62,6 +61,12 @@ CarInitialPoseTool::CarInitialPoseTool()
62
61
{
63
62
shortcut_key_ = ' k' ;
64
63
64
+ enable_interactive_property_ = new rviz_common::properties::BoolProperty (
65
+ " Interactive" , false , " Enable/Disable interactive action by manipulating mouse." ,
66
+ getPropertyContainer ());
67
+ property_frame_ = new rviz_common::properties::TfFrameProperty (
68
+ " Target Frame" , rviz_common::properties::TfFrameProperty::FIXED_FRAME_STRING,
69
+ " The TF frame where the point cloud is output." , getPropertyContainer (), nullptr , true );
65
70
topic_property_ = new rviz_common::properties::StringProperty (
66
71
" Pose Topic" , " /simulation/dummy_perception_publisher/object_info" ,
67
72
" The topic on which to publish dummy object info." , getPropertyContainer (), SLOT (updateTopic ()),
@@ -93,73 +98,44 @@ void CarInitialPoseTool::onInitialize()
93
98
updateTopic ();
94
99
}
95
100
96
- void CarInitialPoseTool::updateTopic ()
97
- {
98
- rclcpp::Node::SharedPtr raw_node = context_->getRosNodeAbstraction ().lock ()->get_raw_node ();
99
- dummy_object_info_pub_ = raw_node->create_publisher <dummy_perception_publisher::msg::Object>(
100
- topic_property_->getStdString (), 1 );
101
- clock_ = raw_node->get_clock ();
102
- }
103
-
104
- void CarInitialPoseTool::onPoseSet (double x, double y, double theta)
101
+ Object CarInitialPoseTool::createObjectMsg () const
105
102
{
106
- dummy_perception_publisher::msg:: Object output_msg ;
103
+ Object object{} ;
107
104
std::string fixed_frame = context_->getFixedFrame ().toStdString ();
108
105
109
106
// header
110
- output_msg .header .frame_id = fixed_frame;
111
- output_msg .header .stamp = clock_->now ();
107
+ object .header .frame_id = fixed_frame;
108
+ object .header .stamp = clock_->now ();
112
109
113
110
// semantic
114
- output_msg .classification .label = autoware_auto_perception_msgs::msg:: ObjectClassification::CAR;
115
- output_msg .classification .probability = 1.0 ;
111
+ object .classification .label = ObjectClassification::CAR;
112
+ object .classification .probability = 1.0 ;
116
113
117
114
// shape
118
- output_msg .shape .type = autoware_auto_perception_msgs::msg:: Shape::BOUNDING_BOX;
115
+ object .shape .type = Shape::BOUNDING_BOX;
119
116
const double width = 1.8 ;
120
117
const double length = 4.0 ;
121
- output_msg .shape .dimensions .x = length;
122
- output_msg .shape .dimensions .y = width;
123
- output_msg .shape .dimensions .z = 2.0 ;
118
+ object .shape .dimensions .x = length;
119
+ object .shape .dimensions .y = width;
120
+ object .shape .dimensions .z = 2.0 ;
124
121
125
122
// initial state
126
- // pose
127
- output_msg.initial_state .pose_covariance .pose .position .x = x;
128
- output_msg.initial_state .pose_covariance .pose .position .y = y;
129
- output_msg.initial_state .pose_covariance .pose .position .z = position_z_->getFloat ();
130
- output_msg.initial_state .pose_covariance .covariance [0 ] =
123
+ object.initial_state .pose_covariance .pose .position .z = position_z_->getFloat ();
124
+ object.initial_state .pose_covariance .covariance [0 ] =
131
125
std_dev_x_->getFloat () * std_dev_x_->getFloat ();
132
- output_msg .initial_state .pose_covariance .covariance [7 ] =
126
+ object .initial_state .pose_covariance .covariance [7 ] =
133
127
std_dev_y_->getFloat () * std_dev_y_->getFloat ();
134
- output_msg .initial_state .pose_covariance .covariance [14 ] =
128
+ object .initial_state .pose_covariance .covariance [14 ] =
135
129
std_dev_z_->getFloat () * std_dev_z_->getFloat ();
136
- output_msg .initial_state .pose_covariance .covariance [35 ] =
130
+ object .initial_state .pose_covariance .covariance [35 ] =
137
131
std_dev_theta_->getFloat () * std_dev_theta_->getFloat ();
138
- tf2::Quaternion quat;
139
- quat.setRPY (0.0 , 0.0 , theta);
140
- output_msg.initial_state .pose_covariance .pose .orientation = tf2::toMsg (quat);
141
- RCLCPP_INFO (
142
- rclcpp::get_logger (" CarInitialPoseTool" ), " Setting pose: %.3f %.3f %.3f %.3f [frame=%s]" , x, y,
143
- position_z_->getFloat (), theta, fixed_frame.c_str ());
144
- // twist
145
- output_msg.initial_state .twist_covariance .twist .linear .x = velocity_->getFloat ();
146
- output_msg.initial_state .twist_covariance .twist .linear .y = 0.0 ;
147
- output_msg.initial_state .twist_covariance .twist .linear .z = 0.0 ;
148
- RCLCPP_INFO (
149
- rclcpp::get_logger (" CarInitialPoseTool" ), " Setting twist: %.3f %.3f %.3f [frame=%s]" ,
150
- velocity_->getFloat (), 0.0 , 0.0 , fixed_frame.c_str ());
151
-
152
- // action
153
- output_msg.action = dummy_perception_publisher::msg::Object::ADD;
154
132
155
- // id
156
133
std::mt19937 gen (std::random_device{}());
157
134
std::independent_bits_engine<std::mt19937, 8 , uint8_t > bit_eng (gen);
158
- std::generate (output_msg .id .uuid .begin (), output_msg .id .uuid .end (), bit_eng);
135
+ std::generate (object .id .uuid .begin (), object .id .uuid .end (), bit_eng);
159
136
160
- dummy_object_info_pub_-> publish (output_msg) ;
137
+ return object ;
161
138
}
162
-
163
139
} // end namespace rviz_plugins
164
140
165
141
#include < pluginlib/class_list_macros.hpp>
0 commit comments