freyja_examples: Ported temporal_provider example#14
freyja_examples: Ported temporal_provider example#14Peter010103 wants to merge 2 commits intounl-nimbus-lab:ros2-develfrom
Conversation
Peter010103
commented
Jan 11, 2022
- Refactored temporal_provider example into ROS2
- Added Lemiscate trajectory example
1355e8d to
86f9e8d
Compare
refactor: ROS2 temporal provider examples include files
86f9e8d to
bb1e8c4
Compare
| 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); |
There was a problem hiding this comment.
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 ) |
There was a problem hiding this comment.
Use ConstSharedPtr for consistency ..
| std::string traj_type; | ||
| int agg_level; | ||
|
|
||
| class Temporal_Traj : public rclcpp::Node |
There was a problem hiding this comment.
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); |
There was a problem hiding this comment.
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; |
There was a problem hiding this comment.
These three are unused, I think?
|
|
||
| class Temporal_Traj : public rclcpp::Node | ||
| { | ||
| TrajRef ref_state; |
There was a problem hiding this comment.
Consider naming class member variables with an _ postfix: ref_state_