Skip to content

Commit

Permalink
Added gps localization setter and corrected gps angle convention
Browse files Browse the repository at this point in the history
  • Loading branch information
artzha committed Dec 3, 2024
1 parent 982e2ae commit 1a2424d
Show file tree
Hide file tree
Showing 4 changed files with 21 additions and 4 deletions.
8 changes: 5 additions & 3 deletions src/navigation/navigation.cc
Original file line number Diff line number Diff line change
Expand Up @@ -503,7 +503,7 @@ void Navigation::UpdateGPS(const GPSPoint& msg) {

// Global coords relative to initial GPS location, heading is absolute
robot_loc_ = gpsToGlobalCoord(initial_gps_loc_, robot_gps_loc_).cast<float>();
robot_angle_ = robot_gps_loc_.heading; // degrees
robot_angle_ = static_cast<float>(gpsToGlobalHeading(robot_gps_loc_));

if (FLAGS_v > 2) {
printf("GPS: %lf %lf\n", msg.lat, msg.lon);
Expand Down Expand Up @@ -1325,6 +1325,10 @@ float Navigation::GetCarrotDist() { return params_.carrot_dist; }

float Navigation::GetObstacleMargin() { return params_.obstacle_margin; }

Eigen::Vector3f Navigation::GetRobotPose() {
return Eigen::Vector3f(robot_loc_.x(), robot_loc_.y(), robot_angle_);
}

float Navigation::GetRobotWidth() { return params_.robot_width; }

float Navigation::GetRobotLength() { return params_.robot_length; }
Expand Down Expand Up @@ -1731,8 +1735,6 @@ bool Navigation::Run(const double& time, Vector2f& cmd_vel,
}
// Local Navigation (Convert global to local coordinates)
local_target_ = Rotation2Df(-robot_angle_) * (carrot - robot_loc_);
// Swap x=y y=-x
// local_target_ = Vector2f(local_target_.y(), -local_target_.x());
printf("Local target %f %f\n", local_target_.x(), local_target_.y());
}
}
Expand Down
1 change: 1 addition & 0 deletions src/navigation/navigation.h
Original file line number Diff line number Diff line change
Expand Up @@ -194,6 +194,7 @@ class Navigation {
std::vector<Eigen::Vector2f> GetPredictedCloud();
float GetCarrotDist();
float GetObstacleMargin();
Eigen::Vector3f GetRobotPose();
float GetRobotWidth();
float GetRobotLength();
const cv::Mat& GetVisualizationImage();
Expand Down
14 changes: 14 additions & 0 deletions src/navigation/navigation_main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -85,6 +85,7 @@ using amrl_msgs::GPSMsg;
using amrl_msgs::graphNavGPSSrv;
using amrl_msgs::NavStatusMsg;
using amrl_msgs::VisualizationMsg;
using amrl_msgs::Localization2DMsg;
using Eigen::Affine3f;
using Eigen::Vector2f;
using Eigen::Vector3f;
Expand Down Expand Up @@ -172,6 +173,7 @@ ros::Publisher fp_pcl_pub_;
ros::Publisher path_pub_;
ros::Publisher carrot_pub_;
ros::Publisher next_gps_goal_pub_;
ros::Publisher localization_pub_;
image_transport::Publisher viz_img_pub_;

// Messages
Expand Down Expand Up @@ -529,6 +531,16 @@ nav_msgs::Path CarrotToNavMsgsPath(const Vector2f& carrot) {
return carrotNav;
}

void PublishLocalization() {
// Publishes robot pose
Localization2DMsg loc_msg;
loc_msg.header.stamp = ros::Time::now();
loc_msg.pose.x = navigation_.GetRobotPose().x();
loc_msg.pose.y = navigation_.GetRobotPose().y();
loc_msg.pose.theta = navigation_.GetRobotPose().z(); // theta
pose_marker_publisher_.publish(loc_msg);
}

void PublishPath() {
const auto path = navigation_.GetPlanPath();
if (path.size() >= 2) {
Expand Down Expand Up @@ -1010,6 +1022,7 @@ int main(int argc, char** argv) {
carrot_pub_ = n.advertise<nav_msgs::Path>("carrot", 1, true);
next_gps_goal_pub_ = n.advertise<GPSMsg>(
"next_gps_goal", 1, true); // Only publish if there is a goal
localization_pub_ = n.advertise<Localization2DMsg>("localization", 1);

// Messages
local_viz_msg_ =
Expand Down Expand Up @@ -1102,6 +1115,7 @@ int main(int argc, char** argv) {
DrawTarget();
DrawPathOptions();
}
PublishLocalization();
PublishVisualizationMarkers();
PublishPath();
PublishNextGPSGoal();
Expand Down
2 changes: 1 addition & 1 deletion src/shared
Submodule shared updated 1 files
+8 −4 math/gps_util.h

0 comments on commit 1a2424d

Please sign in to comment.