From f7d5648526722922cc209c28a31cfb216c216d8e Mon Sep 17 00:00:00 2001 From: Sammy Pfeiffer Date: Thu, 20 Nov 2014 11:26:57 +0100 Subject: [PATCH] Fixed shared_dynamic_cast is not a member of boost --- reemc_hardware_gazebo/src/reemc_hardware_gazebo.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/reemc_hardware_gazebo/src/reemc_hardware_gazebo.cpp b/reemc_hardware_gazebo/src/reemc_hardware_gazebo.cpp index 5aceece..a99b1e0 100644 --- a/reemc_hardware_gazebo/src/reemc_hardware_gazebo.cpp +++ b/reemc_hardware_gazebo/src/reemc_hardware_gazebo.cpp @@ -169,7 +169,7 @@ bool ReemcHardwareGazebo::initSim(const std::string& robot_ns, ROS_DEBUG_STREAM("Registered ankle force-torque sensors."); // Hardware interfaces: Base IMU sensors - imu_sensor_ = boost::shared_dynamic_cast + imu_sensor_ = boost::dynamic_pointer_cast (gazebo::sensors::SensorManager::Instance()->GetSensor("imu_sensor")); // TODO: Fetch from URDF? /*reemc::reemc::base_link::imu_sensor*/ if (!this->imu_sensor_) {