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

freyja_examples: Ported temporal_provider example #14

Open
wants to merge 2 commits into
base: ros2-devel
Choose a base branch
from

Conversation

Peter010103
Copy link

  • Refactored temporal_provider example into ROS2
  • Added Lemiscate trajectory example

@Peter010103 Peter010103 changed the base branch from robomaster to ros2-devel January 11, 2022 20:35
time_reset_sub_ = create_subscription<std_msgs::msg::UInt8>(
"/reset_trajectory_time", 1, std::bind(&Temporal_Traj::timer_reset_cb, this, _1));

traj_pub_ = create_publisher<TrajRef>("/reference_state", 1);
Copy link
Member

Choose a reason for hiding this comment

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

Just use "reference_state" without the /. This helps with namespaces.


void timeResetCallback( const std_msgs::UInt8::ConstPtr &msg )
void Temporal_Traj::timer_reset_cb( std_msgs::msg::UInt8::SharedPtr msg )
Copy link
Member

Choose a reason for hiding this comment

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

Use ConstSharedPtr for consistency ..

std::string traj_type;
int agg_level;

class Temporal_Traj : public rclcpp::Node
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 it might be better to remove the _ in the class name. It is redundant with this case-style, and also will maintain consistency.

TrajRef getHoverReference( const ros::Duration &cur_time )
void Temporal_Traj::traj_update_cb()
{
get_parameter("traj_type", traj_type);
Copy link
Member

Choose a reason for hiding this comment

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

I'm not sure that this is essential (esp. for the purposes of an example). Resetting this parameter on the fly will lead to discontinuous and somewhat unexpected trajectories mid-flight.


rclcpp::Time init_time;
std::string traj_type;
int agg_level;
Copy link
Member

Choose a reason for hiding this comment

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

These three are unused, I think?


class Temporal_Traj : public rclcpp::Node
{
TrajRef ref_state;
Copy link
Member

Choose a reason for hiding this comment

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

Consider naming class member variables with an _ postfix: ref_state_

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

2 participants