35 #include <sensor_msgs/Joy.h> 36 #include <geometry_msgs/Twist.h> 37 #include <std_msgs/Int32.h> 40 #include <robotnik_msgs/enable_disable.h> 41 #include <robotnik_msgs/set_digital_output.h> 42 #include "diagnostic_msgs/DiagnosticStatus.h" 47 #include "ackermann_msgs/AckermannDriveStamped.h" 48 #include <std_srvs/Empty.h> 49 #include "robotnik_msgs/set_mode.h" 50 #include "robotnik_msgs/get_mode.h" 52 #define DEFAULT_MAX_LINEAR_SPEED 3.0 //m/s 53 #define DEFAULT_MAX_ANGULAR_POSITION 2.0 // rads/s 55 #define MAX_NUM_OF_BUTTONS 16 56 #define MAX_NUM_OF_AXES 8 57 #define MAX_NUM_OF_BUTTONS_PS3 19 58 #define MAX_NUM_OF_AXES_PS3 20 60 #define DEFAULT_NUM_OF_BUTTONS 16 61 #define DEFAULT_NUM_OF_AXES 8 63 #define DEFAULT_AXIS_LINEAR_X 1 64 #define DEFAULT_AXIS_ANGULAR 2 65 #define DEFAULT_SCALE_LINEAR 1.0 66 #define DEFAULT_SCALE_ANGULAR 1.0 68 #define DEFAULT_JOY "/joy" 69 #define DEFAULT_HZ 50.0 85 if(iPressed and !value){
88 }
else if(bReleased and value)
112 int SetStateMode(
int state,
int arm_mode,
int platform_mode);
116 void joyCallback(
const sensor_msgs::Joy::ConstPtr& joy);
118 char * StateToString(
int state);
119 int SwitchToState(
int new_state);
123 bool EnableDisable(robotnik_msgs::enable_disable::Request &req, robotnik_msgs::enable_disable::Response &res );
203 axis_linear_speed_(1),
204 axis_angular_position_(2)
263 fAxes.push_back(0.0);
340 ROS_INFO(
"RbcarJoy::EnablaDisable: Setting to %d", req.value);
349 for(
int i = 0; i < joy->axes.size(); i++){
350 this->
fAxes[i] = joy->axes[i];
352 for(
int i = 0; i < joy->buttons.size(); i++){
353 this->
vButtons[i].Press(joy->buttons[i]);
362 double desired_linear_speed = 0.0, desired_angular_position = 0.0;
363 ackermann_msgs::AckermannDriveStamped ref_msg;
375 ref_msg.drive.jerk = 0.0;
376 ref_msg.drive.acceleration = 0.0;
377 ref_msg.drive.steering_angle_velocity = 0.0;
384 ref_msg.drive.steering_angle = desired_angular_position;
385 ref_msg.drive.speed = desired_linear_speed;
403 ref_msg.drive.jerk = 0.0;
404 ref_msg.drive.acceleration = 0.0;
405 ref_msg.drive.steering_angle_velocity = 0.0;
407 ref_msg.drive.steering_angle = 0.0;
408 ref_msg.drive.speed = 0.0;
420 int main(
int argc,
char** argv)
ros::Publisher vel_pub_
It will publish into command velocity (for the robot)
int axis_angular_position_
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void ControlLoop()
Controls the actions and states.
int main(int argc, char **argv)
int button_speed_up_
Number of the button for increase or decrease the speed max of the joystick.
int button_kinematic_mode_
button to change kinematic mode
void publish(const boost::shared_ptr< M > &message) const
double max_linear_speed_
Set the max speed sent to the robot.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void setHardwareID(const std::string &hwid)
int ptz_tilt_up_
buttons to the pan-tilt camera
std::string cmd_service_ptz_
Name of the service to move ptz.
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define DEFAULT_AXIS_ANGULAR
std::vector< float > fAxes
Vector to save the axis values.
std::string joy_topic_
// Name of the joystick's topic
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.
#define DEFAULT_MAX_ANGULAR_POSITION
double max_angular_position_
double desired_freq_
Desired component's freq.
bool bEnable
Flag to enable/disable the communication with the publishers topics.
int button_dead_man_
Number of the DEADMAN button.
#define MAX_NUM_OF_AXES_PS3
ros::ServiceServer enable_disable_srv_
Service clients.
double min_freq_command
Diagnostics min freq.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::Publisher state_pub_
Topic to publish the state.
#define MAX_NUM_OF_BUTTONS
bool EnableDisable(robotnik_msgs::enable_disable::Request &req, robotnik_msgs::enable_disable::Response &res)
Enables/Disables the joystick.
std::string cmd_set_mode_
Name of the service to change the mode.
diagnostic_updater::HeaderlessTopicDiagnostic * sus_joy_freq
Diagnostic to control the reception frequency of the subscribed joy topic.
std::vector< Button > vButtons
Vector to save and control the axis values.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define DEFAULT_NUM_OF_BUTTONS
#define DEFAULT_MAX_LINEAR_SPEED
ros::ServiceClient setKinematicMode
Service to modify the kinematic mode.
void joyCallback(const sensor_msgs::Joy::ConstPtr &joy)
ros::ServiceClient set_digital_outputs_client_
std::string cmd_service_io_
Name of the service where it will be modifying the digital outputs.
double max_freq_command
Diagnostics max freq.
std::string cmd_topic_vel
Name of the topic where it will be publishing the velocity.
#define DEFAULT_NUM_OF_AXES
int num_of_buttons_
Current number of buttons of the joystick.
std::string topic_state_
topic name for the state
ROSCPP_DECL void spinOnce()
diagnostic_updater::Updater updater_pad
General status diagnostic updater.
#define MAX_NUM_OF_BUTTONS_PS3
ros::Subscriber joy_sub_
they will be suscribed to the joysticks
#define DEFAULT_AXIS_LINEAR_X
int kinematic_mode_
kinematic mode