void catapult(const ros::Time &time, const ros::Duration &period)
effort_controllers::JointVelocityController ctrl_wheel_
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
Execute ChassisBase::init. Init necessary handles.
effort_controllers::JointPositionController ctrl_catapult_joint_
geometry_msgs::Twist odometry() override
Calculate current linear_x according to current velocity.
void normal(const ros::Time &time, const ros::Duration &period)
void moveJoint(const ros::Time &time, const ros::Duration &period) override
Calculate correct command and set it to wheel.
double catapult_initial_velocity_