diff --git a/jsk_interactive_markers/jsk_interactive_marker/src/footstep_marker.cpp b/jsk_interactive_markers/jsk_interactive_marker/src/footstep_marker.cpp index c433b2b0e..874c8cb9c 100644 --- a/jsk_interactive_markers/jsk_interactive_marker/src/footstep_marker.cpp +++ b/jsk_interactive_markers/jsk_interactive_marker/src/footstep_marker.cpp @@ -42,7 +42,7 @@ #include #include #include -#include +#include #include #include #include @@ -91,7 +91,7 @@ plan_run_(false), lleg_first_(true) { pnh.param("no_wait", nowait, true); pnh.param("frame_id", marker_frame_id_, std::string("/map")); footstep_pub_ = nh.advertise("footstep_from_marker", 1); - snapit_client_ = nh.serviceClient("snapit"); + snapit_client_ = nh.serviceClient("snapit"); snapped_pose_pub_ = pnh.advertise("snapped_pose", 1); current_pose_pub_ = pnh.advertise("current_pose", 1); estimate_occlusion_client_ = nh.serviceClient("require_estimation"); @@ -296,7 +296,7 @@ void FootstepMarker::resetLegPoses() { geometry_msgs::Pose FootstepMarker::computeLegTransformation(uint8_t leg) { geometry_msgs::Pose new_pose; - jsk_pcl_ros::CallSnapIt srv; + jsk_recognition_msgs::CallSnapIt srv; srv.request.request.header.stamp = ros::Time::now(); srv.request.request.header.frame_id = marker_frame_id_; srv.request.request.target_plane.header.stamp = ros::Time::now();