36 #include <sensor_msgs/Joy.h> 37 #include <geometry_msgs/Twist.h> 38 #include <std_msgs/Int32.h> 41 #include <robotnik_msgs/enable_disable.h> 42 #include <robotnik_msgs/set_digital_output.h> 43 #include "diagnostic_msgs/DiagnosticStatus.h" 50 #include "ackermann_msgs/AckermannDriveStamped.h" 51 #include <std_srvs/Empty.h> 53 #define DEFAULT_MAX_SKID_LINEAR_SPEED 2.0 //m/s 54 #define DEFAULT_MAX_ANGULAR_POSITION 2.0 // rads/s 56 #define MAX_NUM_OF_BUTTONS 16 57 #define MAX_NUM_OF_AXES 8 58 #define MAX_NUM_OF_BUTTONS_PS3 19 59 #define MAX_NUM_OF_AXES_PS3 20 61 #define DEFAULT_NUM_OF_BUTTONS 16 62 #define DEFAULT_NUM_OF_AXES 8 64 #define DEFAULT_AXIS_LINEAR_X 1 65 #define DEFAULT_AXIS_ANGULAR 0 66 #define DEFAULT_SCALE_LINEAR 1.0 67 #define DEFAULT_SCALE_ANGULAR 1.0 70 #define DEFAULT_JOY "/joy" 72 #define DEFAULT_HZ 50.0 87 if(iPressed and !value){
90 }
else if(bReleased and value)
118 int SetStateMode(
int state,
int arm_mode,
int platform_mode);
122 void joyCallback(
const sensor_msgs::Joy::ConstPtr& joy);
124 char * StateToString(
int state);
125 int SwitchToState(
int new_state);
129 bool EnableDisable(robotnik_msgs::enable_disable::Request &req, robotnik_msgs::enable_disable::Response &res );
208 axis_linear_speed_(1),
209 axis_angular_position_(2), nh_(
"~")
263 fAxes.push_back(0.0);
341 ROS_INFO(
"AgvsPad::EnablaDisable: Setting to %d", req.value);
351 for(
int i = 0; i < joy->axes.size(); i++){
352 this->
fAxes[i] = joy->axes[i];
354 for(
int i = 0; i < joy->buttons.size(); i++){
355 this->
vButtons[i].Press(joy->buttons[i]);
364 double desired_linear_speed = 0.0, desired_angular_position = 0.0;
366 ackermann_msgs::AckermannDriveStamped ref_msg;
379 ref_msg.drive.jerk = 0.0;
380 ref_msg.drive.acceleration = 0.0;
381 ref_msg.drive.steering_angle_velocity = 0.0;
386 ref_msg.drive.steering_angle = desired_angular_position;
387 ref_msg.drive.speed = desired_linear_speed;
406 ref_msg.drive.jerk = 0.0;
407 ref_msg.drive.acceleration = 0.0;
408 ref_msg.drive.steering_angle_velocity = 0.0;
410 ref_msg.drive.steering_angle = 0.0;
411 ref_msg.drive.speed = 0.0;
416 std_srvs::Empty empty_srv;
421 std_srvs::Empty empty_srv;
435 int main(
int argc,
char** argv)
bool bEnable
Flag to enable/disable the communication with the publishers topics.
void ControlLoop()
Controls the actions and states.
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
std::vector< float > fAxes
Vector to save the axis values.
int axis_angular_position_
std::string joy_topic_
// Name of the joystick's topic
void publish(const boost::shared_ptr< M > &message) const
std::string topic_state_
topic name for the state
int button_dead_man_
Number of the DEADMAN button.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ros::ServiceServer enable_disable_srv_
Service clients.
ros::ServiceClient raise_elevator_client_
ros::ServiceClient set_digital_outputs_client_
#define DEFAULT_MAX_SKID_LINEAR_SPEED
void setHardwareID(const std::string &hwid)
#define DEFAULT_NUM_OF_BUTTONS
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
std::vector< Button > vButtons
Vector to save and control the axis values.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
diagnostic_updater::HeaderlessTopicDiagnostic * pub_command_freq
Diagnostic to control the frequency of the published command velocity topic.
std::string service_lower_elevator_
Name of the service called to lower the elevator.
#define DEFAULT_NUM_OF_AXES
#define DEFAULT_AXIS_ANGULAR
std::string cmd_service_io_
Name of the service where it will be modifying the digital outputs.
#define DEFAULT_MAX_ANGULAR_POSITION
double min_freq_command
Diagnostics min freq.
#define DEFAULT_AXIS_LINEAR_X
double max_linear_speed_
Set the max speed sent to the robot.
ros::Publisher state_pub_
Topic to publish the state.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::Subscriber joy_sub_
they will be suscribed to the joysticks
diagnostic_updater::Updater updater_pad
General status diagnostic updater.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher vel_pub_
It will publish into command velocity (for the robot)
diagnostic_updater::HeaderlessTopicDiagnostic * sus_joy_freq
Diagnostic to control the reception frequency of the subscribed joy topic.
#define MAX_NUM_OF_AXES_PS3
void joyCallback(const sensor_msgs::Joy::ConstPtr &joy)
double desired_freq_
Desired component's freq.
#define MAX_NUM_OF_BUTTONS
double max_freq_command
Diagnostics max freq.
int button_speed_up_
Number of the button for increase or decrease the speed max of the joystick.
int num_of_buttons_
Current number of buttons of the joystick.
std::string cmd_topic_vel
Name of the topic where it will be publishing the velocity.
ros::ServiceClient lower_elevator_client_
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()
std::string service_raise_elevator_
Name of the service called to raise the elevator.
bool EnableDisable(robotnik_msgs::enable_disable::Request &req, robotnik_msgs::enable_disable::Response &res)
Enables/Disables the joystick.
#define MAX_NUM_OF_BUTTONS_PS3
double max_angular_position_