Skip to content

Commit

Permalink
robot_id_
Browse files Browse the repository at this point in the history
  • Loading branch information
hecperleo committed Feb 20, 2019
1 parent 5386882 commit d5f7b2c
Showing 1 changed file with 7 additions and 7 deletions.
14 changes: 7 additions & 7 deletions uav_abstraction_layer/src/backend_crazyflie.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,23 +51,23 @@ BackendCrazyflie::BackendCrazyflie()

// Init ros communications
ros::NodeHandle nh;
std::string crazyflie_ns = "ual";
std::string crazyflie_ns = "/crazyflie" + robot_id_;
// std::string set_mode_srv = crazyflie_ns + "/set_mode";
// std::string arming_srv = crazyflie_ns + "/cmd/arming";
// std::string get_param_srv = crazyflie_ns + "/param/get";
std::string set_pose_topic = /* crazyflie_ns + */ "/crazyflie/goal";
std::string set_pose_topic = crazyflie_ns + "/goal";
// std::string set_pose_global_topic = crazyflie_ns + "/setpoint_raw/global";
std::string set_vel_topic = /* crazyflie_ns + */ "/crazyflie/cmd_vel";
std::string pose_topic = /* crazyflie_ns + */ "/crazyflie/pose";
std::string set_vel_topic = crazyflie_ns + "/cmd_vel";
std::string pose_topic = crazyflie_ns + "/pose";
// std::string geo_pose_topic = crazyflie_ns + "/global_position/global";
// std::string vel_topic = crazyflie_ns + "/local_position/velocity";
std::string state_topic = /* crazyflie_ns + */ "/crazyflie/state";
std::string state_topic = crazyflie_ns + "/state";
// std::string extended_state_topic = crazyflie_ns + "/extended_state";

// flight_mode_client_ = nh.serviceClient<mavros_msgs::SetMode>(set_mode_srv.c_str());
// arming_client_ = nh.serviceClient<mavros_msgs::CommandBool>(arming_srv.c_str());
takeoff_client_ = nh.serviceClient<std_srvs::Empty>("/crazyflie/takeoff");
land_client_ = nh.serviceClient<std_srvs::Empty>("/crazyflie/land");
takeoff_client_ = nh.serviceClient<std_srvs::Empty>(crazyflie_ns + "/takeoff");
land_client_ = nh.serviceClient<std_srvs::Empty>(crazyflie_ns + "/land");

crazyflie_ref_pose_pub_ = nh.advertise<geometry_msgs::PoseStamped>(set_pose_topic.c_str(), 1);
// mavros_ref_pose_global_pub_ = nh.advertise<mavros_msgs::GlobalPositionTarget>(set_pose_global_topic.c_str(), 1);
Expand Down

0 comments on commit d5f7b2c

Please sign in to comment.