re-add param for database and xbee port

This commit is contained in:
CIM Husky 2017-09-20 12:57:20 -04:00
parent 05e45dd8fc
commit 50095af0f1
4 changed files with 25 additions and 9 deletions

View File

@ -45,7 +45,11 @@ catkin_package(
###########
## Build ##
###########
## Add definitions
add_definitions(
-DDATABASE_PATH="${CMAKE_CURRENT_SOURCE_DIR}/Resources/database.xml"
-DXBEE_CONFIG_PATH="${CMAKE_CURRENT_SOURCE_DIR}/Resources/XBee_Config.xml"
)
## Specify additional locations of header files
include_directories(

View File

@ -9,4 +9,6 @@
<param name="Xbee_Out_To_Buzz" type="str" value="inMavlink" />
<param name="Xbee_In_From_Controller" type="str" value="xbee_cmd" />
<param name="Xbee_Out_To_Controller" type="str" value="mav_dji_cmd" />
<param name="USB_port" type="str" value="/dev/ttyUSB0" />
<param name="Baud_rate" type="double" value="230400" />
</launch>

View File

@ -466,12 +466,11 @@ void PacketsHandler::Send_End_Of_Packet_Ping(const uint8_t packet_ID, const uint
//*****************************************************************************
bool PacketsHandler::Load_Database_Addresses()
{
const std::string FILE_PATH = "/home/ubuntu/ROS_WS/src/xbeemav/Resources/database.xml";
const std::string FILE_PATH = DATABASE_PATH;
if (!boost::filesystem::exists(FILE_PATH))
{
std::cout << "database.xml Not Found." << std::endl;
std::cout << "database.xml Not Found with path: " << FILE_PATH << std::endl;
return false;
}

View File

@ -14,10 +14,11 @@ int main(int argc, char* argv[])
try
{
ros::init(argc, argv, "xbee");
ros::NodeHandle node_handle;
Mist::Xbee::CommunicationManager communication_manager;
const std::string& device = "/dev/ttyUSB0"; // TO DO can be introduced as command.
const std::size_t baud_rate = 230400; // TO DO Can be introduced as command.
std::string device;
double baud_rate;
Mist::Xbee::CommunicationManager::DRONE_TYPE drone_type =
Mist::Xbee::CommunicationManager::DRONE_TYPE::SLAVE;
Mist::Xbee::CommunicationManager::RUNNING_MODE running_mode =
@ -34,8 +35,18 @@ int main(int argc, char* argv[])
running_mode = Mist::Xbee::CommunicationManager::RUNNING_MODE::SWARM;
}
}
if (communication_manager.Init(device, baud_rate))
if (!node_handle.getParam("USB_port", device))
{
std::cout << "Failed to Get Topic Name: param 'USB_port' Not Found." << std::endl;
return EXIT_FAILURE;
}
if (!node_handle.getParam("Baud_rate", baud_rate))
{
std::cout << "Failed to Get Topic Name: param 'Baud_rate' Not Found." << std::endl;
return EXIT_FAILURE;
}
if (communication_manager.Init(device, static_cast<std::size_t>(baud_rate)))
communication_manager.Run(drone_type, running_mode);
}
catch (const std::exception& e)