controls the ART vehicle brake, throttle, steering and transmission More...
controls the ART vehicle brake, throttle, steering and transmission
The pilot receives CarDriveStamped messages from the navigator, then translates them into commands to the servo motor actuators for controlling the speed and direction of the vehicle. It gets odometry information from a separate node.
Subscribes:
Publishes:
typedef dynamic_reconfigure::Server<Config> PilotNode::ReconfigServer [private] |
PilotNode::PilotNode | ( | ros::NodeHandle | node | ) |
void PilotNode::adjustSteering | ( | void | ) | [private] |
Adjust steering angle.
We do not use PID control, because the odometry does not provide accurate yaw speed feedback. Instead, we directly compute the corresponding steering angle. We can use open loop control at this level, because navigator monitors our actual course and will request any steering changes needed to reach its goal.
void PilotNode::halt | ( | void | ) | [private] |
halt -- soft version of hardware E-Stop.
The goal is to bring the vehicle to a halt as quickly as possible, while remaining safely under control. Normally, navigator sends gradually declining speed requests when bringing the vehicle to a controlled stop. The only abrupt requests we see are in "emergency" stop situations, when there was a pause request, or no clear path around an obstacle.
void PilotNode::monitorHardware | ( | void | ) | [private] |
void PilotNode::processCarCommand | ( | const art_msgs::CarCommand::ConstPtr & | msg | ) | [private] |
void PilotNode::processCarDrive | ( | const art_msgs::CarDriveStamped::ConstPtr & | msg | ) | [private] |
void PilotNode::processLearning | ( | const art_msgs::LearningCommand::ConstPtr & | learningIn | ) | [private] |
void PilotNode::reconfig | ( | Config & | newconfig, |
uint32_t | level | ||
) | [private] |
handle dynamic reconfigure service request
newconfig | new configuration from dynamic reconfigure client, becomes the service reply message as updated here. |
level | SensorLevels value (0xffffffff on initial call) |
This is done without any locking because it is called in the same thread as ros::spinOnce() and all the topic subscription callbacks.
void PilotNode::speedControl | ( | void | ) | [private] |
Speed control
Manage the shifter. Inputs are the current and target states. If a gear shift is requested, the vehicle must first be brought to a stop, then one of the transmission shift relays set for one second (then reset), before the vehicle can begin moving in the opposite direction.
void PilotNode::spin | ( | void | ) |
void PilotNode::validateTarget | ( | void | ) | [private] |
boost::shared_ptr<pilot::AccelBase> PilotNode::accel_ [private] |
ros::Subscriber PilotNode::accel_cmd_ [private] |
boost::shared_ptr<device_interface::DeviceBrake> PilotNode::brake_ [private] |
ros::Subscriber PilotNode::car_cmd_ [private] |
Config PilotNode::config_ [private] |
ros::Time PilotNode::current_time_ [private] |
ros::Time PilotNode::goal_time_ [private] |
boost::shared_ptr<device_interface::DeviceImu> PilotNode::imu_ [private] |
bool PilotNode::is_shifting_ [private] |
ros::Subscriber PilotNode::learning_cmd_ [private] |
boost::shared_ptr<device_interface::DeviceOdom> PilotNode::odom_ [private] |
ros::Publisher PilotNode::pilot_state_ [private] |
art_msgs::PilotState PilotNode::pstate_msg_ [private] |
boost::shared_ptr<ReconfigServer> PilotNode::reconfig_server_ [private] |
boost::shared_ptr<device_interface::DeviceShifter> PilotNode::shifter_ [private] |
boost::shared_ptr<device_interface::DeviceSteering> PilotNode::steering_ [private] |
boost::shared_ptr<device_interface::DeviceThrottle> PilotNode::throttle_ [private] |
ros::Duration PilotNode::timeout_ [private] |