Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add path publisher. #147

Closed
wants to merge 2 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@
#include <geometry_msgs/Vector3Stamped.h>
#include <nav_msgs/Odometry.h>
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#include <nav_msgs/Path.h>

namespace rm_chassis_controllers
{
Expand Down Expand Up @@ -153,6 +154,7 @@ class ChassisBase : public controller_interface::MultiInterfaceController<T...>
bool topic_update_ = false;
bool publish_odom_tf_ = false;
bool state_changed_ = true;
bool enable_path_ = false;
enum
{
RAW,
Expand All @@ -163,7 +165,7 @@ class ChassisBase : public controller_interface::MultiInterfaceController<T...>
RampFilter<double>*ramp_x_{}, *ramp_y_{}, *ramp_w_{};
std::string follow_source_frame_{}, command_source_frame_{};

ros::Time last_publish_time_;
ros::Time last_publish_time_, last_path_publish_time_;
geometry_msgs::TransformStamped odom2base_{};
tf2::Transform world2odom_;
geometry_msgs::Vector3 vel_cmd_{}; // x, y
Expand All @@ -177,6 +179,8 @@ class ChassisBase : public controller_interface::MultiInterfaceController<T...>
Command cmd_struct_;
realtime_tools::RealtimeBuffer<Command> cmd_rt_buffer_;
realtime_tools::RealtimeBuffer<nav_msgs::Odometry> odom_buffer_;
ros::Publisher path_pub_;
nav_msgs::Path path_;
};

} // namespace rm_chassis_controllers
28 changes: 28 additions & 0 deletions rm_chassis_controllers/src/chassis_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,7 @@ bool ChassisBase<T...>::init(hardware_interface::RobotHW* robot_hw, ros::NodeHan
!controller_nh.getParam("power/vel_coeff", velocity_coeff_) ||
!controller_nh.getParam("power/effort_coeff", effort_coeff_) ||
!controller_nh.getParam("power/power_offset", power_offset_))

{
ROS_ERROR("Some chassis params doesn't given (namespace: %s)", controller_nh.getNamespace().c_str());
return false;
Expand All @@ -65,6 +66,7 @@ bool ChassisBase<T...>::init(hardware_interface::RobotHW* robot_hw, ros::NodeHan
max_odom_vel_ = getParam(controller_nh, "max_odom_vel", 0);
enable_odom_tf_ = getParam(controller_nh, "enable_odom_tf", true);
publish_odom_tf_ = getParam(controller_nh, "publish_odom_tf", false);
enable_path_ = getParam(controller_nh, "enable_path", false);

// Get and check params for covariances
XmlRpc::XmlRpcValue twist_cov_list;
Expand Down Expand Up @@ -114,6 +116,8 @@ bool ChassisBase<T...>::init(hardware_interface::RobotHW* robot_hw, ros::NodeHan
if (!pid_follow_.init(ros::NodeHandle(controller_nh, "pid_follow")))
return false;

path_pub_ = controller_nh.advertise<nav_msgs::Path>("/ori_path", 10);

return true;
}

Expand Down Expand Up @@ -349,6 +353,30 @@ void ChassisBase<T...>::updateOdom(const ros::Time& time, const ros::Duration& p
topic_update_ = false;
}

if (enable_path_)
{
path_.header.stamp = time;
path_.header.frame_id = "odom";
geometry_msgs::PoseStamped this_pose_stamped;
this_pose_stamped.header.frame_id = "odom";
this_pose_stamped.header.stamp = time;
this_pose_stamped.pose.position.x = odom2base_.transform.translation.x;
this_pose_stamped.pose.position.y = odom2base_.transform.translation.y;
this_pose_stamped.pose.position.z = odom2base_.transform.translation.z;
this_pose_stamped.pose.orientation.x = odom2base_.transform.rotation.x;
this_pose_stamped.pose.orientation.y = odom2base_.transform.rotation.y;
this_pose_stamped.pose.orientation.z = odom2base_.transform.rotation.z;
this_pose_stamped.pose.orientation.w = odom2base_.transform.rotation.w;
GuraMumei marked this conversation as resolved.
Show resolved Hide resolved

double path_publish_rate = 1.0;
if (path_publish_rate > 0.0 && last_path_publish_time_ + ros::Duration(1.0 / path_publish_rate) < time)
{
path_.poses.push_back(this_pose_stamped);
path_pub_.publish(path_); // path
last_path_publish_time_ = time;
}
}

robot_state_handle_.setTransform(odom2base_, "rm_chassis_controllers");

if (publish_rate_ > 0.0 && last_publish_time_ + ros::Duration(1.0 / publish_rate_) < time)
Expand Down
Loading