@@ -163,25 +163,25 @@ void AirsimROSWrapper::create_ros_pubs_from_settings_json()
163
163
164
164
// bind to a single callback. todo optimal subs queue length
165
165
// bind multiple topics to a single callback, but keep track of which vehicle name it was by passing curr_vehicle_name as the 2nd argument
166
- drone->vel_cmd_body_frame_sub_ = nh_->create_subscription <airsim_interfaces::msg::VelCmd>(topic_prefix + " /vel_cmd_body_frame" , 1 , [&](const airsim_interfaces::msg::VelCmd::SharedPtr msg) { this ->vel_cmd_body_frame_cb (msg, vehicle_ros->vehicle_name_ ); }); // todo ros::TransportHints().tcpNoDelay();
167
166
168
- drone->vel_cmd_world_frame_sub_ = nh_->create_subscription <airsim_interfaces::msg::VelCmd>(topic_prefix + " /vel_cmd_world_frame" , 1 , [&](const airsim_interfaces::msg::VelCmd::SharedPtr msg) { this ->vel_cmd_world_frame_cb (msg, vehicle_ros->vehicle_name_ ); });
167
+ std::function<void (const airsim_interfaces::msg::VelCmd::SharedPtr)> fcn_vel_cmd_body_frame_sub = std::bind (&AirsimROSWrapper::vel_cmd_body_frame_cb, this , _1, vehicle_ros->vehicle_name_ );
168
+ drone->vel_cmd_body_frame_sub_ = nh_->create_subscription <airsim_interfaces::msg::VelCmd>(topic_prefix + " /vel_cmd_body_frame" , 1 , fcn_vel_cmd_body_frame_sub); // todo ros::TransportHints().tcpNoDelay();
169
169
170
- drone->takeoff_srvr_ = nh_->create_service <airsim_interfaces::srv::Takeoff>(topic_prefix + " /takeoff" ,
171
- [&](std::shared_ptr<airsim_interfaces::srv::Takeoff::Request> request,
172
- std::shared_ptr<airsim_interfaces::srv::Takeoff::Response>
173
- response) { this ->takeoff_srv_cb (request, response, vehicle_ros->vehicle_name_ ); });
170
+ std::function<void (const airsim_interfaces::msg::VelCmd::SharedPtr)> fcn_vel_cmd_world_frame_sub = std::bind (&AirsimROSWrapper::vel_cmd_world_frame_cb, this , _1, vehicle_ros->vehicle_name_ );
171
+ drone->vel_cmd_world_frame_sub_ = nh_->create_subscription <airsim_interfaces::msg::VelCmd>(topic_prefix + " /vel_cmd_world_frame" , 1 , fcn_vel_cmd_world_frame_sub);
174
172
175
- drone->land_srvr_ = nh_->create_service <airsim_interfaces::srv::Land>(topic_prefix + " /land" ,
176
- [&](std::shared_ptr<airsim_interfaces::srv::Land::Request> request,
177
- std::shared_ptr<airsim_interfaces::srv::Land::Response>
178
- response) { this ->land_srv_cb (request, response, vehicle_ros->vehicle_name_ ); });
173
+ std::function<bool (std::shared_ptr<airsim_interfaces::srv::Takeoff::Request>, std::shared_ptr<airsim_interfaces::srv::Takeoff::Response>)> fcn_takeoff_srvr = std::bind (&AirsimROSWrapper::takeoff_srv_cb, this , _1, _2, vehicle_ros->vehicle_name_ );
174
+ drone->takeoff_srvr_ = nh_->create_service <airsim_interfaces::srv::Takeoff>(topic_prefix + " /takeoff" , fcn_takeoff_srvr);
175
+
176
+ std::function<bool (std::shared_ptr<airsim_interfaces::srv::Land::Request>, std::shared_ptr<airsim_interfaces::srv::Land::Response>)> fcn_land_srvr = std::bind (&AirsimROSWrapper::land_srv_cb, this , _1, _2, vehicle_ros->vehicle_name_ );
177
+ drone->land_srvr_ = nh_->create_service <airsim_interfaces::srv::Land>(topic_prefix + " /land" , fcn_land_srvr);
179
178
180
179
// vehicle_ros.reset_srvr = nh_->create_service(curr_vehicle_name + "/reset",&AirsimROSWrapper::reset_srv_cb, this);
181
180
}
182
181
else {
183
182
auto car = static_cast <CarROS*>(vehicle_ros.get ());
184
- car->car_cmd_sub_ = nh_->create_subscription <airsim_interfaces::msg::CarControls>(topic_prefix + " /car_cmd" , 1 , [&](const airsim_interfaces::msg::CarControls::SharedPtr msg) { this ->car_cmd_cb (msg, vehicle_ros->vehicle_name_ ); });
183
+ std::function<void (const airsim_interfaces::msg::CarControls::SharedPtr)> fcn_car_cmd_sub = std::bind (&AirsimROSWrapper::car_cmd_cb, this , _1, vehicle_ros->vehicle_name_ );
184
+ car->car_cmd_sub_ = nh_->create_subscription <airsim_interfaces::msg::CarControls>(topic_prefix + " /car_cmd" , 1 , fcn_car_cmd_sub);
185
185
car->car_state_pub_ = nh_->create_publisher <airsim_interfaces::msg::CarState>(topic_prefix + " /car_state" , 10 );
186
186
}
187
187
0 commit comments