diff --git a/nao_dcm_apps/nao_dcm_camera/include/nao_dcm_camera/nao_camera.h b/nao_dcm_apps/nao_dcm_camera/include/nao_dcm_camera/nao_camera.h index 4e616d1..e5346ad 100644 --- a/nao_dcm_apps/nao_dcm_camera/include/nao_dcm_camera/nao_camera.h +++ b/nao_dcm_apps/nao_dcm_camera/include/nao_dcm_camera/nao_camera.h @@ -49,7 +49,7 @@ OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISE #include #include -using std::string; +using etk::String; using std::cerr; using std::endl; @@ -92,7 +92,7 @@ private: AL::ALVideoDeviceProxy video_proxy_; public: // Constructor/Destructor - NaoCamera(boost::shared_ptr broker, const std::string& name); + NaoCamera(boost::shared_ptr broker, const etk::String& name); ~NaoCamera(); bool initialize(); diff --git a/nao_dcm_apps/nao_dcm_camera/src/nao_camera.cpp b/nao_dcm_apps/nao_dcm_camera/src/nao_camera.cpp index f51dccf..d10cbfa 100644 --- a/nao_dcm_apps/nao_dcm_camera/src/nao_camera.cpp +++ b/nao_dcm_apps/nao_dcm_camera/src/nao_camera.cpp @@ -23,7 +23,7 @@ OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISE #include #include "nao_dcm_camera/nao_camera.h" -using std::vector; +using etk::Vector; NaoCamera::NaoCamera(boost::shared_ptr broker, const string &name) : AL::ALModule(broker,name),is_connected_(false),reconfiguring_(false) diff --git a/nao_dcm_robot/nao_dcm_driver/include/nao_dcm_driver/nao.h b/nao_dcm_robot/nao_dcm_driver/include/nao_dcm_driver/nao.h index bb5528b..d8e309a 100644 --- a/nao_dcm_robot/nao_dcm_driver/include/nao_dcm_driver/nao.h +++ b/nao_dcm_robot/nao_dcm_driver/include/nao_dcm_driver/nao.h @@ -61,8 +61,8 @@ OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISE #include -using std::string; -using std::vector; +using etk::String; +using etk::Vector; namespace AL { @@ -131,36 +131,36 @@ private: AL::DCMProxy dcm_proxy_; // IMU - vector imu_names_; + vector imu_names_; // Sonars - vector sonar_names_; + vector sonar_names_; // FSRs - vector fsr_names_; + vector fsr_names_; // Tactile - vector tactile_names_; + vector tactile_names_; // Bumper - vector bumper_names_; + vector bumper_names_; // Joints - vector joints_names_; - vector joint_temperature_names_; + vector joints_names_; + vector joint_temperature_names_; // Battery - vector battery_names_; + vector battery_names_; // LEDs - vector led_names_; + vector led_names_; // Joint States hardware_interface::JointStateInterface jnt_state_interface_; hardware_interface::PositionJointInterface jnt_pos_interface_; int number_of_joints_; - vector joint_names_; + vector joint_names_; vector joint_commands_; vector joint_angles_; vector joint_velocities_; vector joint_efforts_; public: // Constructor/Destructor - Nao(boost::shared_ptr broker, const std::string& name); + Nao(boost::shared_ptr broker, const etk::String& name); ~Nao(); bool initialize(); @@ -188,10 +188,10 @@ public: // ALMemoryProxy Wrapper Methods void insertDataToMemory(const string& key, const AL::ALValue& value); AL::ALValue getDataFromMemory(const string& key); - void subscribeToEvent(const std::string& name, const std::string& callback_module, - const std::string& callback_method); - void subscribeToMicroEvent(const std::string& name, const std::string& callback_module, - const std::string& callback_method, const string& callback_message=""); + void subscribeToEvent(const etk::String& name, const etk::String& callback_module, + const etk::String& callback_method); + void subscribeToMicroEvent(const etk::String& name, const etk::String& callback_module, + const etk::String& callback_method, const string& callback_message=""); void unsubscribeFromEvent(const string& name, const string& callback_module); void unsubscribeFromMicroEvent(const string& name, const string& callback_module); void raiseEvent(const string& name, const AL::ALValue& value); diff --git a/nao_dcm_robot/nao_dcm_driver/src/nao.cpp b/nao_dcm_robot/nao_dcm_driver/src/nao.cpp index 0d31e2f..3004622 100644 --- a/nao_dcm_robot/nao_dcm_driver/src/nao.cpp +++ b/nao_dcm_robot/nao_dcm_driver/src/nao.cpp @@ -53,7 +53,7 @@ bool Nao::initialize() "Device/SubDeviceList/InertialSensor/AccelerometerX/Sensor/Value", "Device/SubDeviceList/InertialSensor/AccelerometerY/Sensor/Value", "Device/SubDeviceList/InertialSensor/AccelerometerZ/Sensor/Value"}; - imu_names_ = vector(imu, end(imu)); + imu_names_ = vector(imu, end(imu)); // Sonar Memory Keys const char* sonar[] = {"Device/SubDeviceList/US/Left/Sensor/Value", @@ -76,7 +76,7 @@ bool Nao::initialize() "Device/SubDeviceList/US/Right/Sensor/Value7", "Device/SubDeviceList/US/Right/Sensor/Value8", "Device/SubDeviceList/US/Right/Sensor/Value9"}; - sonar_names_ = vector(sonar, end(sonar)); + sonar_names_ = vector(sonar, end(sonar)); // Foot Contact Memory Keys const char* fsr[] = {"Device/SubDeviceList/LFoot/FSR/FrontLeft/Sensor/Value", @@ -93,7 +93,7 @@ bool Nao::initialize() "Device/SubDeviceList/LFoot/FSR/CenterOfPressure/Y/Sensor/Value", "Device/SubDeviceList/RFoot/FSR/CenterOfPressure/X/Sensor/Value", "Device/SubDeviceList/RFoot/FSR/CenterOfPressure/Y/Sensor/Value"}; - fsr_names_ = vector(fsr, end(fsr)); + fsr_names_ = vector(fsr, end(fsr)); // Tactile Memory Keys const char* tactile[] = {"Device/SubDeviceList/Head/Touch/Front/Sensor/Value", @@ -105,19 +105,19 @@ bool Nao::initialize() "Device/SubDeviceList/RHand/Touch/Back/Sensor/Value", "Device/SubDeviceList/RHand/Touch/Left/Sensor/Value", "Device/SubDeviceList/RHand/Touch/Right/Sensor/Value"}; - tactile_names_ = vector(tactile, end(tactile)); + tactile_names_ = vector(tactile, end(tactile)); // Bumper Memory Keys const char* bumper[] = {"Device/SubDeviceList/LFoot/Bumper/Left/Sensor/Value", "Device/SubDeviceList/LFoot/Bumper/Right/Sensor/Value", "Device/SubDeviceList/RFoot/Bumper/Left/Sensor/Value", "Device/SubDeviceList/RFoot/Bumper/Right/Sensor/Value"}; - bumper_names_ = vector(bumper, end(bumper)); + bumper_names_ = vector(bumper, end(bumper)); // Battery Memory Keys const char* battery[] = {"Device/SubDeviceList/Battery/Charge/Sensor/Value", "Device/SubDeviceList/Battery/Temperature/Sensor/Value"}; - battery_names_ = vector(battery, end(battery)); + battery_names_ = vector(battery, end(battery)); // LED Memory Keys const char* led[] = {"Device/SubDeviceList/ChestBoard/Led/Blue/Actuator/Value", @@ -209,7 +209,7 @@ bool Nao::initialize() "Device/SubDeviceList/RFoot/Led/Blue/Actuator/Value", "Device/SubDeviceList/RFoot/Led/Green/Actuator/Value", "Device/SubDeviceList/RFoot/Led/Red/Actuator/Value"}; - led_names_ = vector(led, end(led)); + led_names_ = vector(led, end(led)); // Joints Initialization const char* joint[] = {"HeadYaw", @@ -238,9 +238,9 @@ bool Nao::initialize() "RKneePitch", "RAnklePitch", "RAnkleRoll"}; - joint_names_ = vector(joint, end(joint)); + joint_names_ = vector(joint, end(joint)); - for(vector::iterator it=joint_names_.begin();it!=joint_names_.end();it++) + for(vector::iterator it=joint_names_.begin();it!=joint_names_.end();it++) { if((*it=="RHand" || *it=="LHand" || *it == "RWristYaw" || *it == "LWristYaw") && (body_type_ == "H21")) { @@ -248,10 +248,10 @@ bool Nao::initialize() it--; continue; } - joints_names_.push_back("Device/SubDeviceList/"+(*it)+"/Position/Sensor/Value"); + joints_names_.pushBack("Device/SubDeviceList/"+(*it)+"/Position/Sensor/Value"); if(*it!="RHipYawPitch") { - joint_temperature_names_.push_back("Device/SubDeviceList/"+(*it)+"/Temperature/Sensor/Value"); + joint_temperature_names_.pushBack("Device/SubDeviceList/"+(*it)+"/Temperature/Sensor/Value"); } } number_of_joints_ = joint_names_.size(); @@ -847,7 +847,7 @@ void Nao::publishBaseFootprint(const ros::Time &ts) } tf::Vector3 new_origin = (tf_odom_to_right_foot.getOrigin() + tf_odom_to_left_foot.getOrigin())/2.0; - double height = std::min(tf_odom_to_left_foot.getOrigin().getZ(), tf_odom_to_right_foot.getOrigin().getZ()); + double height = etk::min(tf_odom_to_left_foot.getOrigin().getZ(), tf_odom_to_right_foot.getOrigin().getZ()); new_origin.setZ(height); double roll, pitch, yaw; @@ -1115,7 +1115,7 @@ void Nao::checkBattery(diagnostic_updater::DiagnosticStatusWrapper &stat) return; } int status = 0; - string message = "Battery: "+boost::lexical_cast(float(batt[0])*100.0f)+"\% charged! "; + string message = "Battery: "+boost::lexical_cast(float(batt[0])*100.0f)+"\% charged! "; if(float(batt[0])*100.0f<50.0f) status = 1; else if(float(batt[0])*100.0f<20.0f) diff --git a/nao_dcm_robot/nao_dcm_driver/src/nao_driver.cpp b/nao_dcm_robot/nao_dcm_driver/src/nao_driver.cpp index d79589b..2c435a6 100644 --- a/nao_dcm_robot/nao_dcm_driver/src/nao_driver.cpp +++ b/nao_dcm_robot/nao_dcm_driver/src/nao_driver.cpp @@ -25,7 +25,7 @@ OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISE #include #include -using std::string; +using etk::String; using std::cerr; using std::endl;