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

feat: frame aware depth control #61

Open
wants to merge 16 commits into
base: main
Choose a base branch
from
Open

Conversation

eminmeydanoglu
Copy link
Contributor

@eminmeydanoglu eminmeydanoglu commented Nov 2, 2024

Closes #69

  1. Added a new field to SetDepth.srv: frame_id. This addition was necessary so that we could pass frame_id as a parameter to ros service. Ros service can now be called by;
    rosservice call /taluy/set_depth "target_depth: 5.0 frame_id: 'taluy/base_link/imu_link'"
  2. Updated the function targetdepthhandler to take frame_id into account and transform the target_depth accordingly. The function now checks whether any frame_id is provided, and makes the appropriate transformation if we have one. If none, it passes the target depth directly.

Output of depth_controller_node, passed the above argument.

emin@emin  ~  rosrun auv_control depth_controller_node.py
[INFO] [1730549202.232636]: DepthControllerNode has started.
[INFO] [1730549202.348437]: Published cmd_pose with target depth: 0.0
[INFO] [1730549202.448895]: Published cmd_pose with target depth: 0.0
[INFO] [1730549202.548592]: Published cmd_pose with target depth: 0.0
[INFO] [1730549202.648865]: Published cmd_pose with target depth: 0.0
[INFO] [1730549203.548702]: Published cmd_pose with target depth: 0.0
[INFO] [1730549203.648719]: Published cmd_pose with target depth: 0.0
[INFO] [1730549203.748993]: Published cmd_pose with target depth: 0.0
[INFO] [1730549203.848313]: Published cmd_pose with target depth: 0.0
[INFO] [1730549203.948296]: Published cmd_pose with target depth: 0.0
[INFO] [1730549204.048224]: Published cmd_pose with target depth: 0.0
[INFO] [1730549204.148642]: Published cmd_pose with target depth: 0.0
[INFO] [1730549204.190259]: Received SetDepth request with target depth: 5.0 and frame_id: taluy/base_link/imu_link
[INFO] [1730549204.192819]: Transform from taluy/base_link/imu_link to taluy/base_link obtained successfully.
[INFO] [1730549204.194964]: Translation: x=-0.199, y=0.0, z=-0.0108
[INFO] [1730549204.197106]: Rotation: x=0.0, y=0.0, z=1.0, w=6.123233995736766e-17
[INFO] [1730549204.199998]: Target depth transformed to base frame: 4.9892
[INFO] [1730549204.248530]: Published cmd_pose with target depth: 4.9892
[INFO] [1730549204.348178]: Published cmd_pose with target depth: 4.9892
[INFO] [1730549205.749011]: Published cmd_pose with target depth: 4.9892
[INFO] [1730549205.848305]: Published cmd_pose with target depth: 4.9892
^C[INFO] [1730549205.948610]: Published cmd_pose with target depth: 4.9892

Copy link
Member

@senceryazici senceryazici left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good work. thank you for the PR.

The frame handling and transformations should be on the position controller side (the node that subscribes to cmd_pose.) This requires the cmd_pose type to be geometry_msgs/PoseStamped instead of geometry_msgs/Pose. then the header.frame_id will be interpreted same as your approach.

Adding frame_id to the SetDepth hence to the depth_controller_node is a good idea, with above implementation all you need to do in that node is

def ..callback(req: SetDepthRequest):
    pose_stamped.header.frame_id = req.frame_id
    # continue publishing cmd_pose as usual.

.gitignore Outdated
@@ -37,3 +37,4 @@

*__pycache__*
*.pyc
auv_simulation/
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

not necessary, or unrelated to this PR

@@ -23,11 +23,11 @@ model:
- [0, 0, 0, 0, 0.0, 0]
- [0, 0, 0, 0, 0, 7.98053]

#kp: [0.0, 0.0, 1.5, 0.0, 0.0, 0.0, 1.0, 1.0, 1.0, 5.0, 0.0, 1.0]
#kp: [0.0, 0.0, 1.5, 0.0, 0.0, 0.0, 1.0, 1.0, 1.0, 0.1, 0.0, 1.0]
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

these are unrelated, please rollback them

#ki: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
#kd: [0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0, 1.0, 1.0, 0.0, 0.0, 1.0]

kp: [0.0, 0.0, 1.5, 0.0, 0.0, 0.0, 1.0, 1.0, 1.0, 0.1, 0.0, 1.0]
kp: [0.0, 0.0, 1.5, 0.0, 0.0, 0.0, 1.0, 1.0, 1.0, 5.0, 0.0, 1.0]
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

these are unrelated, please rollback them

@eminmeydanoglu eminmeydanoglu marked this pull request as draft November 6, 2024 16:57
@eminmeydanoglu
Copy link
Contributor Author

Hi, made some changes. Looking forward to hear from you @senceryazici

@eminmeydanoglu eminmeydanoglu marked this pull request as ready for review November 8, 2024 13:12
Copy link
Member

@senceryazici senceryazici left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good work, we're getting there.

rospy.loginfo(f"Received SetDepth request with target depth: {req.target_depth} and frame_id: {req.frame_id}")

# Check if frame_id is provided
if not req.frame_id:
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

when the frame_id is empty, the system will keep using the latest frame id?

Here we want to call the set depth with -5.0 for example, which will default to whatever controller defaults to. but,

suppose we call depth=-4.0 frame_id="torpedo" first, then we call depth=-5.0 without frame_id (assuming will default to 'odom'), it will not, instead it will go to depth=-5.0 at frame_id="torpedo"

simply, if the frame_id is empty, then empty the self.frame_id

if not req.frame_id
    self.target_frame_id =  req.frame_id
self.target_frame_id = req.frame_id

After this there is no point in the if statement, so why not just remove the if, and set the target_frame_id = req.frame_id at all times

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Got it.
self.target_frame_id = req.frame_id # If the target frame_id is not given, simply empty the frame_id


# Parameters
self.base_frame = rospy.get_param("~base_link", "taluy/base_link") # Default to "taluy/base_link" if not set
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think we don't need this?



class DepthControllerNode:
def __init__(self):
rospy.init_node("depth_controller_node")
rospy.loginfo("DepthControllerNode has started.")

self.tf_buffer = tf2_ros.Buffer()
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

also this should not be needed

rospy.loginfo("DepthControllerNode has started.")

self.tf_buffer = tf2_ros.Buffer()
self.tf_listener = tf2_ros.TransformListener(self.tf_buffer)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this as well

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Yes, transform handling is now at controller_ros.h


# Initialize internal state
self.target_depth = 0.0
self.current_depth = 0.0
self.target_frame_id = "taluy/base_link" # default to "taluy/base_link" if not set
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think we must leave this empty,

self.target_frame_id = ""

since the controller node will already default to some frame if the given frame is empty. let's not default to some value in 2 places. harder to maintain.

Copy link
Contributor Author

@eminmeydanoglu eminmeydanoglu Nov 8, 2024

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

True, controller_ros.h handles it already

from auv_msgs.srv import SetDepth, SetDepthRequest, SetDepthResponse
import time
import tf2_geometry_msgs
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

these needed?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

TF libraries are no longer needed here. Also, time was not being used, thus removed as well.

tf2::doTransform(msg->pose, transformed_pose, transform_stamped);
ROS_DEBUG_STREAM_THROTTLE(10.0,"Transformed pose from " << source_frame << " to " << base_frame);
} else {
ROS_DEBUG_STREAM_THROTTLE(10.0, "Using original pose (no transformation needed)");
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hmm, the position controller state vector accepts targets in odom frame by default, not base link. desired_state_.head(6)

maybe this base_frame is meant to be "odom", in any case let's rename it to default_frame

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Changing base_frame ---> default_frame

if (!source_frame.empty() && source_frame[0] == '/') {
source_frame = source_frame.substr(1);
}

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

lets make this a bit more readable.

const auto is_transform_required = !source_frame.empty() || source_frame == base_frame;

then

if (is_transform_required) {
try {
transform_stamped = tf_buffer.lookupTransform(base_frame, source_frame, ros::Time(0));
tf2::doTransform(msg->pose, transformed_pose, transform_stamped);
ROS_DEBUG_STREAM_THROTTLE(10.0,"Transformed pose from " << source_frame << " to " << base_frame); }
} catch (tf2::TransformException &ex) {
rest of the catch.
}

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hmm. In this implementation,
const auto is_transform_required = !source_frame.empty() || source_frame == base_frame;
the transformation would be considered required even if source_frame is the same as default frame. But transforming to the same frame seems unnecessary. Do we need to transform the source frame to the default frame if they are the exact same?
This one will not cause unnecessary transformation:
const auto is_transform_required = !source_frame.empty() && source_frame != default_frame; // only transform if not empty and not the same as default frame

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Correct,

const auto is_transform_required = !source_frame.empty() && source_frame != default_frame;

}
} catch (tf2::TransformException &ex) {
ROS_DEBUG_STREAM_THROTTLE(10.0,"Could not transform from " << msg->header.frame_id << " to " << base_frame << ": " << ex.what());
transformed_pose = msg->pose;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Let's drop the message if failing to transform and never write to desired_state_.head(6)

example
suppose the frame "frame1" is 50m above the odom. (not likely but anyways :D), target of -50 at frame1 is actually target of 0 at odom, so it should be surfacing (odom is at water surface). but if you type it wrong or the transform between frames were not valid for some couple of seconds. then -50 at default frame is used with this code. then the robot will hit the bottom.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

instead, drop the message and return from the function, ignoring the target pose.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hmm, never thought about that.

catch (tf2::TransformException &ex) { // if transformation failed, ignore the target pose.
        return;


std_msgs::Float64 z_msg;
z_msg.data = transformed_pose.position.z;
transformed_pose_z_pub_.publish(z_msg);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I guess this is for debugging. After making sure the PR acts as expected, let's remove this publisher to avoid confusion.

odometry_sub_ =
nh_.subscribe("odometry", 1, &ControllerROS::odometry_callback, this);
cmd_vel_sub_ =
nh_.subscribe("cmd_vel", 1, &ControllerROS::cmd_vel_callback, this);
cmd_pose_sub_ =
nh_.subscribe("cmd_pose", 1, &ControllerROS::cmd_pose_callback, this);
cmd_pose_sub_ = nh_.subscribe("cmd_pose_stamped", 1,
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

lets leave this cmd_pose

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Alright. Changing the publishing part in depth_controller_node.py

# Initialize publisher
        self.cmd_pose_pub = rospy.Publisher(
            "/taluy/cmd_pose", PoseStamped, queue_size=10)

auv::common::conversions::convert<geometry_msgs::Pose,
ControllerBase::Vector>(*msg);
void cmd_pose_callback(const geometry_msgs::PoseStamped::ConstPtr& msg) {
const std::string default_frame = "odom";
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

maybe get this from rosparam

const auto nh_priv = ros::NodeHandle{"~"};
position_control_default_frame_ = nh_priv.param<std::string>("position_control_default_frame", "odom");


...

private:
  std::string position_control_default_frame_;

geometry_msgs::Pose transformed_pose;


std::string source_frame = msg->header.frame_id;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

const auto source_frame = msg->header.frame_id;

if (!source_frame.empty() && source_frame[0] == '/') {
source_frame = source_frame.substr(1);
}

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Correct,

const auto is_transform_required = !source_frame.empty() && source_frame != default_frame;

} // the / causes errors.

try {
const auto is_transform_required =
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

const std::optional<std::string> get_source_frame(const std::string& source_frame) {
    if (source_frame.empty()) {
        return std::nullopt;
     } 

    if (source_frame == position_control_default_frame_) {
        return std::nullopt;
    }
    // transform is required.
    if (source_frame[0] == '/') {
        return source_frame.substr(1);
    }
    return source_frame;
}

void callback(.....) {
 // ...
const auto source_frame = get_source_frame(msg->header.frame_id);

auto transformed_pose = msg->pose;
if (source_frame.has_value()) {
    try {
        transformed_pose = ...(from=source_frame.value())...;
        tf2::doTransform....
     } catch ... {
       return;
     }
} 
}

 desired_state_.head(6) = auv::common::conversions::convert<
        geometry_msgs::Pose, ControllerBase::Vector>(transformed_pose);
    latest_command_time_ = ros::Time::now();


desired_state_.head(6) = auv::common::conversions::convert<
geometry_msgs::Pose, ControllerBase::Vector>(transformed_pose);

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

New cmd_pose_callback structure with a get_source_frame helper function.

kd_; // Parameters to be dynamically reconfigured
std::string config_file_; // Path to the config file

std::string position_control_default_frame_;
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

member variable decleration for position_control_default_frame_

@@ -21,33 +21,43 @@ def __init__(self):
)

# Initialize publisher
self.cmd_pose_pub = rospy.Publisher("/taluy/cmd_pose", Pose, queue_size=10)
self.cmd_pose_pub = rospy.Publisher(
"/taluy/cmd_pose", PoseStamped, queue_size=10)
Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

publishes to cmd_pose instead of cmd_pose_stamped

Copy link
Member

@senceryazici senceryazici left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks good let's see the test results

Copy link
Contributor Author

@eminmeydanoglu eminmeydanoglu left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Sure. Here is a video of me testing the new code:

deepin-screen-recorder_microsoft-edge_20241113030220.mp4

What is happening here?

  1. I call the service without any tf, and the code fails to transform (nothing passed to desired_state_)
  2. I define tf's and watch the transformed_pose change.
  3. I kill the tf, and function now fails to transform again. (since there is no valid transform now.)

Fix for a potential bug

We used to use ros::Time(0) for the transformation time. But this might lead to some unwanted behavior. For example;

"Maybe there existed a transformation between frame_1 and default_frame 10 minutes ago. We received a service call with a target_pose in frame_1 (maybe not likely, but still). Even though there's currently no transformation between these frames and we are absolutely not sure the last known transform is still valid, our code would have gone ahead and transformed the pose anyway. Now, that won't happen thanks to ros::Time::now() using the time of the function callback."

@senceryazici
Copy link
Member

Looks good, I'm curious about the hardware tests though.

@eminmeydanoglu
Copy link
Contributor Author

eminmeydanoglu commented Nov 19, 2024

Looks good, I'm curious about the hardware tests though.

We will be testing the features of the new implementation in the next pool test.

@senceryazici senceryazici added the needs hardware test features that needs to be tested on the hardware label Nov 23, 2024
@ozanhakantunca ozanhakantunca added the needs simulation test Features that needs to be tested on the simulation label Jan 2, 2025
@eminmeydanoglu eminmeydanoglu changed the title adding frame_id information to depth controller node feat: frame aware depth control Jan 17, 2025
@eminmeydanoglu
Copy link
Contributor Author

eminmeydanoglu commented Jan 17, 2025

In the last pool test, we successfully validated the frame-aware depth control functionality. Its only that my frame aware controller had an interesting interaction with @talhabw 's heading control implementation. Since my code was transforming everything in command pose, it also transformed the last three components, causing the heading control to request alignment with depth control's reference frame. So, I modified the transform handling process to only transform the z axis pose. The depth control now correctly responds to frame-specific commands and don't cause heading control to go silly. With that, I think this project is complete and bug free.

Irrelevantly, I want to mention that the way we handle command timeout is not bug-free. In this PR, notice how we avoid updating the desired state if there is a problem

void cmd_pose_callback(const geometry_msgs::PoseStamped::ConstPtr& msg) {
         ..... 
         try {
         //transform z
      } catch (tf2::TransformException& ex) { // If unsuccessful, exit and don't update desired state
        ROS_DEBUG("Failed to transform pose");
        return;

So if the source frame is missing, we dont update the desired state (which is correct). But guess what, the desired state will stay the same with the last update unless there comes a new service call. So if the frame is gone missing after it was used even once, that desired state update will be kept forever. For more information about the issue refer to #115

@eminmeydanoglu
Copy link
Contributor Author

This PR was thoroughly tested during the last pool test, including edge cases and its interaction with heading control, and everything worked flawlessly. I believe it’s ready to go! @senceryazici

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
needs hardware test features that needs to be tested on the hardware needs simulation test Features that needs to be tested on the simulation
Projects
None yet
Development

Successfully merging this pull request may close these issues.

add proper frame handling for cmd_pose
3 participants