Skip to content

Commit 528b21f

Browse files
Jayasinghe, Oshada (Data61, Pullenvale)Jayasinghe, Oshada (Data61, Pullenvale)
authored andcommitted
Removed ros namespace from standard includes header
1 parent d5c96c2 commit 528b21f

File tree

2 files changed

+4
-5
lines changed

2 files changed

+4
-5
lines changed

include/syropod_highlevel_controller/standard_includes.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,6 @@
6060
#define GRAVITY_ACCELERATION -9.81 ///< Approximate gravitational acceleration (m/s/s)
6161

6262
using namespace std;
63-
using namespace ros;
6463

6564
/// Converts Degrees to Radians.
6665
/// @param[in] degrees Value in degrees to be converted to radians

src/state_controller.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -703,7 +703,7 @@ void StateController::generateExternalTargetTransforms(void)
703703
try
704704
{
705705
geometry_msgs::TransformStamped target_transform;
706-
target_transform = transform_buffer_.lookupTransform(frame_id, past, "walk_plane", Time(0), fixed_frame_id_);
706+
target_transform = transform_buffer_.lookupTransform(frame_id, past, "walk_plane", ros::Time(0), fixed_frame_id_);
707707
external_target.transform_ = Pose(target_transform.transform);
708708
leg_stepper->setExternalTarget(external_target);
709709
}
@@ -722,7 +722,7 @@ void StateController::generateExternalTargetTransforms(void)
722722
try
723723
{
724724
geometry_msgs::TransformStamped default_transform;
725-
default_transform = transform_buffer_.lookupTransform(frame_id, past, "walk_plane", Time(0), fixed_frame_id_);
725+
default_transform = transform_buffer_.lookupTransform(frame_id, past, "walk_plane", ros::Time(0), fixed_frame_id_);
726726
external_target.transform_ = Pose(default_transform.transform);
727727
leg_stepper->setExternalDefault(external_target);
728728
}
@@ -741,7 +741,7 @@ void StateController::generateExternalTargetTransforms(void)
741741
try
742742
{
743743
geometry_msgs::TransformStamped target_transform;
744-
target_transform = transform_buffer_.lookupTransform("base_link", Time(0), frame_id, past, fixed_frame_id_);
744+
target_transform = transform_buffer_.lookupTransform("base_link", ros::Time(0), frame_id, past, fixed_frame_id_);
745745
external_target.transform_ = Pose(target_transform.transform);
746746
leg_poser->setExternalTarget(external_target);
747747
}
@@ -951,7 +951,7 @@ void StateController::publishFrameTransforms(void)
951951
try
952952
{
953953
fixed_frame_id_ = "odom";
954-
transform_buffer_.lookupTransform("base_link", "odom", Time(0));
954+
transform_buffer_.lookupTransform("base_link", "odom", ros::Time(0));
955955
}
956956
catch (tf2::TransformException &ex)
957957
{

0 commit comments

Comments
 (0)