Hiep update
This commit is contained in:
@@ -12,7 +12,7 @@
|
||||
#define STATUS_SUCCESSED 1
|
||||
#define STATUS_ERROR -1
|
||||
|
||||
amr_control::OpcUAServerAPI::OpcUAServerAPI(const ros::NodeHandle &nh, std::shared_ptr<move_base_core::BaseNavigation> move_base,
|
||||
amr_control::OpcUAServerAPI::OpcUAServerAPI(const ros::NodeHandle &nh, std::shared_ptr<robot::move_base_core::BaseNavigation> move_base,
|
||||
std::shared_ptr<loc_core::BaseLocalization> loc_base, std::shared_ptr<AmrMonitor> monitor)
|
||||
{
|
||||
this->nh_ = nh;
|
||||
@@ -3457,7 +3457,7 @@ void amr_control::OpcUAServerAPI::resetState()
|
||||
|
||||
ros::Publisher amr_control::OpcUAServerAPI::init_pub_;
|
||||
std::shared_ptr<amr_comunication::AmrOpcUAServer> amr_control::OpcUAServerAPI::server_ptr_ = nullptr;
|
||||
std::shared_ptr<move_base_core::BaseNavigation> amr_control::OpcUAServerAPI::move_base_ptr_ = nullptr;
|
||||
std::shared_ptr<robot::move_base_core::BaseNavigation> amr_control::OpcUAServerAPI::move_base_ptr_ = nullptr;
|
||||
std::shared_ptr<loc_core::BaseLocalization> amr_control::OpcUAServerAPI::loc_base_ptr_ = nullptr;
|
||||
std::shared_ptr<amr_control::AmrMonitor> amr_control::OpcUAServerAPI::monitor_ptr_ = nullptr;
|
||||
nav_2d_msgs::Twist2D amr_control::OpcUAServerAPI::cmd_vel_max_;
|
||||
|
||||
Reference in New Issue
Block a user